├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── README.md ├── examples ├── copyright_notice.txt ├── cow.ply ├── point_cloud_io.rviz └── some_cows.bag ├── include └── point_cloud_io │ ├── Read.hpp │ └── Write.hpp ├── launch ├── example_read.launch └── example_write.launch ├── package.xml ├── src ├── Read.cpp ├── Write.cpp ├── read_node.cpp └── write_node.cpp └── test └── empty_test.cpp /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | *.obj 6 | 7 | # Compiled Dynamic libraries 8 | *.so 9 | *.dylib 10 | *.dll 11 | 12 | # Compiled Static libraries 13 | *.lai 14 | *.la 15 | *.a 16 | *.lib 17 | 18 | # Executables 19 | *.exe 20 | *.out 21 | *.app 22 | 23 | # Eclipse 24 | .cproject 25 | .project 26 | .settings 27 | 28 | # Files written by the example 29 | examples/received_cloud_* 30 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5.1) 2 | project(point_cloud_io) 3 | 4 | set(CMAKE_CXX_STANDARD 17) 5 | add_compile_options(-Wall -Wextra -Wpedantic -Werror=return-type) 6 | set(CMAKE_EXPORT_COMPILE_COMMANDS ON) 7 | 8 | # Options. 9 | option(BUILD_WITH_VTK_SUPPORT "Build package with support for VTK files." OFF) 10 | if(BUILD_WITH_VTK_SUPPORT) 11 | message("point_cloud_io will be built with support for VTK files.") 12 | add_definitions(-DHAVE_VTK) 13 | endif() 14 | 15 | set(CATKIN_PACKAGE_DEPENDENCIES 16 | pcl_ros 17 | roscpp 18 | sensor_msgs 19 | ) 20 | 21 | find_package(catkin REQUIRED 22 | COMPONENTS 23 | ${CATKIN_PACKAGE_DEPENDENCIES} 24 | ) 25 | 26 | catkin_package( 27 | INCLUDE_DIRS 28 | include 29 | CATKIN_DEPENDS 30 | ${CATKIN_PACKAGE_DEPENDENCIES} 31 | ) 32 | 33 | include_directories( 34 | include 35 | SYSTEM 36 | ${catkin_INCLUDE_DIRS} 37 | ) 38 | 39 | ########### 40 | ## Build ## 41 | ########### 42 | add_executable(read 43 | src/read_node.cpp 44 | src/Read.cpp 45 | ) 46 | target_link_libraries(read 47 | ${catkin_LIBRARIES} 48 | ) 49 | 50 | add_executable(write 51 | src/write_node.cpp 52 | src/Write.cpp 53 | ) 54 | target_link_libraries(write 55 | ${catkin_LIBRARIES} 56 | ) 57 | 58 | ############# 59 | ## Install ## 60 | ############# 61 | install( 62 | TARGETS 63 | read 64 | write 65 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 66 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 67 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 68 | ) 69 | install( 70 | DIRECTORY 71 | include/${PROJECT_NAME}/ 72 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 73 | ) 74 | install( 75 | DIRECTORY 76 | examples 77 | launch 78 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 79 | ) 80 | 81 | find_package(cmake_clang_tools QUIET) 82 | if(cmake_clang_tools_FOUND) 83 | add_default_clang_tooling( 84 | TARGETS 85 | read 86 | write 87 | ) 88 | endif(cmake_clang_tools_FOUND) 89 | 90 | ############## 91 | ## Test ## 92 | ############## 93 | if(CATKIN_ENABLE_TESTING) 94 | catkin_add_gtest(test_${PROJECT_NAME} 95 | test/empty_test.cpp 96 | ) 97 | add_dependencies(test_${PROJECT_NAME} 98 | read 99 | write 100 | ) 101 | target_include_directories(test_${PROJECT_NAME} PRIVATE 102 | include 103 | ) 104 | target_include_directories(test_${PROJECT_NAME} SYSTEM PUBLIC 105 | ${catkin_INCLUDE_DIRS} 106 | ) 107 | target_link_libraries(test_${PROJECT_NAME} 108 | gtest_main 109 | ${catkin_LIBRARIES} 110 | ) 111 | 112 | ################### 113 | ## Code_coverage ## 114 | ################### 115 | find_package(cmake_code_coverage QUIET) 116 | if(cmake_code_coverage_FOUND) 117 | add_gtest_coverage( 118 | TEST_BUILD_TARGETS 119 | test_${PROJECT_NAME} 120 | ) 121 | endif() 122 | endif() -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright 2019, ANYbotics AG. 2 | 3 | Redistribution and use in source and binary forms, with or without 4 | modification, are permitted provided that the following conditions 5 | are met: 6 | 7 | 1. Redistributions of source code must retain the above copyright 8 | notice, this list of conditions and the following disclaimer. 9 | 10 | 2. Redistributions in binary form must reproduce the above copyright 11 | notice, this list of conditions and the following disclaimer in 12 | the documentation and/or other materials provided with the 13 | distribution. 14 | 15 | 3. Neither the name of the copyright holder nor the names of its 16 | contributors may be used to endorse or promote products derived 17 | from this software without specific prior written permission. 18 | 19 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 20 | "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 21 | LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 22 | A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 23 | HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 24 | SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 25 | LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 26 | DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 27 | THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 28 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Point Cloud IO 2 | ====================== 3 | 4 | Overview 5 | --------------- 6 | 7 | These are two simple [ROS] point cloud helper nodes. **_read_** reads a point cloud from file (ply or vtk) and publishes it as a [sensor_msgs/PointCloud2] message. **_write_** subscribes to a [sensor_msgs/PointCloud2] topic and writes received messages to seperate files (ply, pcd). 8 | 9 | For visualization, make sure to set the **Decay Time** in the **PointCloud2** tab in [rviz] to a high number to get the point cloud visible for a long time. 10 | 11 | This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed. 12 | 13 | **Author: Péter Fankhauser, Remo Diethelm
14 | Affiliation: [ANYbotics](https://www.anybotics.com/)
15 | Maintainer: Remo Diethelm, rdiethelm@anybotics.com
** 16 | 17 | This projected was initially developed at ETH Zurich (Autonomous Systems Lab & Robotic Systems Lab). 18 | 19 | [This work is conducted as part of ANYmal Research, a community to advance legged robotics.](https://www.anymal-research.org/) 20 | 21 | The source code is released under a [BSD 3-Clause license](LICENSE). 22 | 23 | Installation 24 | ------------ 25 | 26 | ### Dependencies 27 | 28 | This software is built on the Robot Operating System ([ROS]), which needs to be [installed](http://wiki.ros.org) first. Additionaly, the it depends on following software: 29 | 30 | - [Point Cloud Library (PCL)](http://pointclouds.org/). 31 | 32 | 33 | ### Building 34 | 35 | In order to build Point Cloud IO, clone the latest version from this repository into your catkin workspace and compile the package using ROS. 36 | 37 | cd ~/catkin_workspace/src 38 | git clone https://github.com/anybotics/point_cloud_io.git 39 | cd ../ 40 | catkin build point_cloud_io 41 | 42 | Note: building the tool with support for the VTK file format is disabled by default. To enable it, run `catkin build point_cloud_io --cmake-args -DBUILD_WITH_VTK_SUPPORT=True` instead. 43 | 44 | Usage 45 | ------------ 46 | 47 | To create your own launch-file, you can use the examples from `point_cloud_io/launch/...`. 48 | 49 | 50 | ### Read 51 | 52 | Load and publish a ply or vtk file with 53 | 54 | rosrun point_cloud_io read _file_path:=/home/user/my_point_cloud.ply _topic:=/my_topic _frame:=/sensor_frame 55 | 56 | Optionally, you can also add `_rate:=1.0` to have the node publish your point cloud at the specified rate. 57 | 58 | 59 | ### Write 60 | 61 | Subscribe and save point clouds to a ply file with 62 | 63 | rosrun point_cloud_io write _topic:=/your_topic _folder_path:=/home/user/my_point_clouds 64 | 65 | Optionally, you can set parameters to fit the point cloud file names to your needs: 66 | 67 | - `_file_prefix:=my_prefix` (default: "point_cloud") 68 | - `_file_ending:=my_ending` (default: "ply", currently only format which is supported for writing) 69 | - `_add_counter_to_path:=false` (default: `true`) 70 | - `_add_frame_id_to_path:=true` (default: `false`) 71 | - `_add_stamp_sec_to_path:=true` (default: `false`) 72 | - `_add_stamp_nsec_to_path:=true` (default: `false`) 73 | 74 | 75 | Bugs & Feature Requests 76 | ------------ 77 | 78 | Please report bugs and request features using the [Issue Tracker](https://github.com/anybotics/point_cloud_io/issues). 79 | 80 | 81 | [ROS]: http://www.ros.org 82 | [rviz]: http://wiki.ros.org/rviz 83 | [sensor_msgs/PointCloud2]: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html 84 | -------------------------------------------------------------------------------- /examples/copyright_notice.txt: -------------------------------------------------------------------------------- 1 | The cow.ply demo files was taken from http://people.sc.fsu.edu/~jburkardt/data/ply/ply.html 2 | by John Burkardt and is distributed under the GNU PGPL license: 3 | http://people.sc.fsu.edu/~jburkardt/txt/gnu_lgpl.txt 4 | -------------------------------------------------------------------------------- /examples/cow.ply: -------------------------------------------------------------------------------- 1 | ply 2 | format ascii 1.0 3 | element vertex 2903 4 | property float32 x 5 | property float32 y 6 | property float32 z 7 | end_header 8 | 0.605538 0.183122 -0.472278 9 | 0.649223 0.1297 -0.494875 10 | 0.601082 0.105512 -0.533343 11 | 0.691245 0.0569483 -0.524762 12 | 0.652035 0.0379582 -0.542332 13 | 0.551138 0.035353 -0.528984 14 | 0.531619 0.0862931 -0.518267 15 | 0.50737 0.153473 -0.480014 16 | 0.553695 0.167654 -0.487671 17 | 0.489856 0.196293 -0.459547 18 | 0.526708 0.218281 -0.46742 19 | 0.628928 0.180988 -0.437145 20 | 0.480463 0.124842 -0.462924 21 | 0.504377 0.066104 -0.487561 22 | 0.456951 0.221023 -0.409198 23 | 0.470214 0.17237 -0.445199 24 | 0.466203 0.150109 -0.379214 25 | 0.574705 0.0229441 -0.40214 26 | 0.469174 0.102158 -0.387329 27 | 0.510774 0.0400168 -0.40009 28 | 0.508936 0.149267 -0.301834 29 | 0.496042 0.222658 -0.319061 30 | 0.454575 0.204404 -0.365716 31 | 0.514049 0.0891451 -0.307022 32 | 0.541124 0.0500849 -0.301199 33 | 0.5957 0.0385092 -0.30689 34 | 0.627165 0.0234026 -0.41067 35 | 0.647535 0.0403254 -0.320944 36 | 0.66388 0.13171 -0.457855 37 | 0.710429 0.0770625 -0.498851 38 | 0.684065 0.125508 -0.420276 39 | 0.733973 0.0561901 -0.447249 40 | 0.644123 0.183809 -0.391095 41 | 0.676281 0.128527 -0.351192 42 | 0.706459 0.0674132 -0.350672 43 | 0.643921 0.173649 -0.361089 44 | 0.566021 0.179392 -0.295398 45 | 0.539074 0.263199 -0.314758 46 | 0.587515 0.120549 -0.29631 47 | 0.622563 0.209606 -0.350649 48 | -1.59618 0.160182 -0.534918 49 | -1.54804 0.10676 -0.557514 50 | -1.60109 0.0825683 -0.595979 51 | -1.50173 0.0340085 -0.587402 52 | -1.54493 0.015014 -0.604971 53 | -1.65613 0.0124087 -0.591624 54 | -1.67765 0.0633488 -0.580908 55 | -1.70437 0.130528 -0.54265 56 | -1.65332 0.144709 -0.550311 57 | -1.72367 0.173349 -0.522187 58 | -1.68306 0.195336 -0.53006 59 | -1.5704 0.158048 -0.499785 60 | -1.73402 0.101902 -0.525564 61 | -1.70767 0.0431597 -0.550201 62 | -1.75993 0.198078 -0.471833 63 | -1.74532 0.14943 -0.507839 64 | -1.74974 0.127169 -0.441854 65 | -1.63016 0 -0.46478 66 | -1.74647 0.0792137 -0.449969 67 | -1.70062 0.0170769 -0.462731 68 | -1.70264 0.126327 -0.364474 69 | -1.71685 0.199714 -0.381701 70 | -1.76255 0.18146 -0.428352 71 | -1.69701 0.0662054 -0.369662 72 | -1.66717 0.0271406 -0.363839 73 | -1.60703 0.0155649 -0.369526 74 | -1.57235 0.000458356 -0.473306 75 | -1.5499 0.0173855 -0.383583 76 | -1.53188 0.108766 -0.52049 77 | -1.48058 0.0541182 -0.561491 78 | -1.50964 0.102568 -0.482916 79 | -1.45464 0.0332504 -0.509889 80 | -1.55366 0.160869 -0.453734 81 | -1.51822 0.105583 -0.413832 82 | -1.48496 0.044469 -0.413312 83 | -1.55388 0.150709 -0.423723 84 | -1.63974 0.156453 -0.358034 85 | -1.66943 0.240259 -0.377394 86 | -1.61605 0.0976043 -0.35895 87 | -1.57742 0.186666 -0.413289 88 | 0.649227 0.1297 0.499118 89 | 0.605542 0.183122 0.476524 90 | 0.553699 0.167654 0.491917 91 | 0.691249 0.0569483 0.529006 92 | 0.601086 0.105512 0.537589 93 | 0.531623 0.0862931 0.522513 94 | 0.551142 0.035353 0.533229 95 | 0.652039 0.0379582 0.546576 96 | 0.507374 0.153473 0.48426 97 | 0.48986 0.196293 0.463793 98 | 0.663884 0.13171 0.462099 99 | 0.470218 0.17237 0.449445 100 | 0.480467 0.124842 0.46717 101 | 0.504381 0.066104 0.491807 102 | 0.510777 0.0400168 0.404336 103 | 0.466205 0.150109 0.38346 104 | 0.469177 0.102158 0.391575 105 | 0.496044 0.222658 0.323306 106 | 0.508938 0.149267 0.30608 107 | 0.514051 0.0891451 0.311268 108 | 0.574708 0.0229441 0.406386 109 | 0.541126 0.0500849 0.305445 110 | 0.627168 0.0234026 0.414916 111 | 0.595702 0.0385092 0.311136 112 | 0.710433 0.0770625 0.503095 113 | 0.684068 0.125508 0.42452 114 | 0.628932 0.180988 0.441391 115 | 0.676283 0.128527 0.355436 116 | 0.733977 0.0561901 0.451493 117 | 0.644126 0.183809 0.395339 118 | 0.566023 0.179392 0.299644 119 | 0.587517 0.120549 0.300556 120 | 0.643923 0.173649 0.365332 121 | 0.647537 0.0403254 0.325188 122 | 0.706461 0.0674132 0.354916 123 | -1.54803 0.10676 0.561775 124 | -1.59617 0.160182 0.53918 125 | -1.65331 0.144709 0.554573 126 | -1.50172 0.0340085 0.591662 127 | -1.60108 0.0825683 0.600241 128 | -1.67764 0.0633488 0.585169 129 | -1.65612 0.0124087 0.595886 130 | -1.54492 0.015014 0.609233 131 | -1.70436 0.130528 0.546911 132 | -1.72366 0.173349 0.526449 133 | -1.53187 0.108766 0.524752 134 | -1.74531 0.14943 0.512101 135 | -1.73401 0.101902 0.529826 136 | -1.70766 0.0431597 0.554462 137 | -1.70061 0.0170769 0.466992 138 | -1.74973 0.127169 0.446116 139 | -1.74646 0.0792137 0.454231 140 | -1.71684 0.199714 0.385963 141 | -1.70263 0.126327 0.368736 142 | -1.697 0.0662054 0.373924 143 | -1.63015 0 0.469042 144 | -1.66716 0.0271406 0.368101 145 | -1.57234 0.000458356 0.477568 146 | -1.60702 0.0155649 0.373787 147 | -1.48057 0.0541182 0.565751 148 | -1.50963 0.102568 0.487176 149 | -1.57039 0.158048 0.504047 150 | -1.51821 0.105583 0.418092 151 | -1.45463 0.0332504 0.514149 152 | -1.55365 0.160869 0.457996 153 | -1.63973 0.156453 0.362295 154 | -1.61604 0.0976043 0.363212 155 | -1.55387 0.150709 0.427985 156 | -1.54989 0.0173855 0.387845 157 | -1.48495 0.044469 0.417572 158 | 0.454577 0.204404 0.369962 159 | -1.76254 0.18146 0.432614 160 | 1.84195 2.46396 -0.258957 161 | 1.8418 2.44429 -0.264842 162 | 1.8295 2.44864 -0.26828 163 | 1.86318 2.44713 -0.212434 164 | 1.84994 2.4514 -0.256211 165 | 1.85457 2.42902 -0.23424 166 | 1.82981 2.42307 -0.254496 167 | 1.79736 2.43626 -0.264586 168 | 1.78509 2.46143 -0.273988 169 | 1.81729 2.46141 -0.274738 170 | 1.80134 2.48559 -0.272027 171 | 1.8505 2.48169 -0.233042 172 | 1.82946 2.46513 -0.270674 173 | 2.25726 2.12461 -0.070485 174 | 2.28528 2.11337 -0.0803594 175 | 2.26443 2.09603 -0.109937 176 | 2.23169 2.10643 -0.13241 177 | 2.23292 2.14189 -0.0803724 178 | 2.20327 2.14362 -0.140274 179 | 2.19946 2.1674 -0.1339 180 | 2.2165 2.15902 -0.0904537 181 | 2.20782 2.19458 -0.123333 182 | 2.23614 2.1814 -0.113146 183 | 2.27295 2.14698 -0.0929268 184 | 2.23694 2.12935 -0.0776923 185 | 2.30231 2.14627 -0.0451959 186 | 1.83393 2.49193 -0.256065 187 | 1.84995 2.4514 0.260446 188 | 1.82947 2.46513 0.274909 189 | 1.8173 2.46141 0.278974 190 | 1.86319 2.44713 0.216669 191 | 1.85051 2.48169 0.237277 192 | 1.85458 2.42902 0.238476 193 | 1.82982 2.42307 0.258731 194 | 1.84181 2.44429 0.269077 195 | 1.82951 2.44864 0.272516 196 | 1.79737 2.43626 0.268822 197 | 1.80135 2.48559 0.276263 198 | 1.7851 2.46143 0.278224 199 | 1.84196 2.46396 0.263193 200 | 1.83394 2.49193 0.260301 201 | 2.26444 2.09603 0.114171 202 | 2.25727 2.12461 0.0747181 203 | 2.23695 2.12935 0.0819253 204 | 2.20328 2.14362 0.144508 205 | 2.23293 2.14189 0.0846054 206 | 2.21651 2.15902 0.0946869 207 | 2.20783 2.19458 0.127567 208 | 2.19947 2.1674 0.138133 209 | 2.23615 2.1814 0.11738 210 | 2.27296 2.14698 0.0971596 211 | 2.2317 2.10643 0.136644 212 | 0.668827 1.21893 -0.38685 213 | 0.720807 1.2603 -0.368644 214 | 0.719458 1.17347 -0.35277 215 | 0.777596 1.28243 -0.328698 216 | 0.769318 1.18236 -0.323836 217 | 0.820999 1.26462 -0.278692 218 | 0.834937 1.193 -0.243485 219 | 0.766563 1.12818 -0.30936 220 | 0.710272 1.11127 -0.333498 221 | 0.619266 1.10488 -0.36014 222 | 0.641011 1.16565 -0.378222 223 | 0.696086 1.07703 -0.321958 224 | 0.609581 1.07003 -0.343446 225 | 0.680437 1.0328 -0.294923 226 | 0.595559 1.01689 -0.315706 227 | 0.660931 0.971349 -0.247981 228 | 0.754383 1.04123 -0.274628 229 | 0.741388 0.985688 -0.235859 230 | 0.782062 1.01467 -0.233782 231 | 0.812319 1.05858 -0.227206 232 | 0.765095 1.09244 -0.296774 233 | 0.835369 1.11467 -0.237688 234 | 0.853204 1.23733 -0.232606 235 | 0.917982 1.19301 -0.170324 236 | 0.874024 1.11837 -0.2058 237 | 0.913441 1.11668 -0.175216 238 | 0.894209 1.04965 -0.191099 239 | 0.866504 1.0129 -0.202238 240 | 0.832182 0.968263 -0.208652 241 | 0.76707 0.938914 -0.210913 242 | 0.726066 0.937217 -0.215714 243 | 0.649969 0.945244 -0.232068 244 | 0.575 0.953765 -0.286608 245 | 0.963144 1.18808 -0.123396 246 | 0.949333 1.11506 -0.135434 247 | 0.9336 1.02924 -0.14425 248 | 0.903298 0.982911 -0.15437 249 | 0.857798 0.933029 -0.157619 250 | 0.780268 0.900903 -0.168168 251 | 0.714741 0.900929 -0.169781 252 | 0.647249 0.904658 -0.187928 253 | 0.561158 0.905893 -0.242893 254 | 0.9679 1.18021 0.00212122 255 | 0.950642 1.10528 0.00212128 256 | 0.934985 1.02157 0.00212134 257 | 0.901986 0.972208 0.00212146 258 | 0.851552 0.929309 0.00212165 259 | 0.775407 0.89042 0.00212193 260 | 0.693398 0.887105 0.00212223 261 | 0.613603 0.899567 0.00212253 262 | 0.504841 0.91232 0.00212293 263 | 0.928297 1.38586 -0.227969 264 | 0.864436 1.45062 -0.288527 265 | 0.908182 1.50137 -0.252618 266 | 0.974732 1.42097 -0.186969 267 | 0.941389 1.32181 -0.187952 268 | 0.903818 1.35305 -0.24147 269 | 0.843247 1.37512 -0.294535 270 | 0.825279 1.33367 -0.292992 271 | 0.812469 1.3612 -0.352947 272 | 0.977673 1.29096 -0.148901 273 | 1.00087 1.2648 -0.113257 274 | 1.00962 1.25555 0.00212106 275 | 1.02812 1.29864 -0.114518 276 | 1.0328 1.29295 0.00212098 277 | 1.00415 1.33449 -0.141993 278 | -0.761904 0.92178 -0.39424 279 | -0.577606 0.890901 -0.403666 280 | -0.641479 0.823748 -0.358932 281 | -0.590359 0.81446 -0.351928 282 | -0.528116 0.831299 -0.360846 283 | -0.369486 0.905434 -0.379211 284 | -0.376301 0.859039 -0.350624 285 | -0.383204 0.823412 -0.243371 286 | -0.581101 0.805167 -0.246416 287 | -0.391372 0.806882 -0.166846 288 | -0.125792 0.931032 -0.294272 289 | -0.130015 0.884055 -0.175063 290 | -0.144865 0.865792 0.00212533 291 | -0.410084 0.797317 0.00212631 292 | 0.415744 0.379789 -0.404217 293 | 0.439151 0.382628 -0.414928 294 | 0.454556 0.302969 -0.431661 295 | 0.487442 0.398405 -0.390287 296 | 0.522565 0.407389 -0.394999 297 | 0.549331 0.332949 -0.41469 298 | 0.537302 0.407305 -0.361348 299 | 0.565258 0.330502 -0.370018 300 | 0.422906 0.295855 -0.432693 301 | 0.423131 0.270795 -0.426676 302 | 0.452802 0.241309 -0.421871 303 | 0.417255 0.229288 -0.429479 304 | 0.589983 0.275591 -0.373294 305 | 0.580263 0.266514 -0.415338 306 | 0.473031 0.312879 -0.437352 307 | 0.465269 0.397135 -0.396066 308 | 0.411715 0.22212 -0.354026 309 | 0.42612 0.230482 -0.306753 310 | 0.441183 0.289591 -0.309786 311 | 0.423727 0.393798 -0.322697 312 | 0.408021 0.371273 -0.361215 313 | 0.410295 0.277892 -0.36491 314 | 0.531368 0.261463 -0.422925 315 | 0.501032 0.32676 -0.4167 316 | 0.495203 0.250715 -0.436193 317 | 0.476055 0.244126 -0.432574 318 | 0.540506 0.347941 -0.334004 319 | 0.572395 0.271623 -0.342878 320 | 0.477083 0.302537 -0.293216 321 | 0.515949 0.335162 -0.30782 322 | 0.488918 0.402297 -0.307326 323 | 0.46995 0.406 -0.309976 324 | 0.527855 0.40034 -0.338403 325 | -1.54697 0.845956 -0.328292 326 | -1.59236 0.813428 -0.404103 327 | -1.52624 0.924482 -0.433412 328 | -1.62813 0.763859 -0.440734 329 | -1.56059 0.915066 -0.475845 330 | -1.66896 0.772539 -0.475492 331 | -1.60357 0.921356 -0.490317 332 | -1.71593 0.780301 -0.486301 333 | -1.64433 0.943423 -0.495461 334 | -1.76668 0.794667 -0.477396 335 | -1.69198 0.968232 -0.478763 336 | -1.88037 0.827234 -0.395964 337 | -1.8839 0.826503 -0.333973 338 | -1.83485 0.948188 -0.294472 339 | -1.81223 1.00124 -0.317275 340 | -1.80512 1.00153 -0.388431 341 | -1.82548 0.948568 -0.389343 342 | -1.73577 0.476367 -0.464428 343 | -1.74253 0.598564 -0.459654 344 | -1.69432 0.606926 -0.454139 345 | -1.73886 0.673118 -0.472534 346 | -1.68529 0.673299 -0.466671 347 | -1.75559 0.676129 -0.470141 348 | -1.77503 0.472986 -0.449096 349 | -1.78837 0.587151 -0.439508 350 | -1.80852 0.688242 -0.441029 351 | -1.82195 0.804586 -0.427932 352 | -1.81724 0.468763 -0.418935 353 | -1.83579 0.5869 -0.416793 354 | -1.86338 0.687541 -0.408691 355 | -1.69884 0.477425 -0.459323 356 | -1.66744 0.602293 -0.43175 357 | -1.65078 0.678452 -0.431116 358 | -1.61673 0.743308 -0.384954 359 | -1.65585 0.658712 -0.376239 360 | -1.67764 0.584436 -0.387691 361 | -1.68469 0.496424 -0.394938 362 | -1.67421 0.491416 -0.429489 363 | -1.64837 0.731001 -0.34019 364 | -1.68195 0.652753 -0.354137 365 | -1.71738 0.652078 -0.33572 366 | -1.72763 0.574553 -0.363738 367 | -1.69325 0.742286 -0.315041 368 | -1.75716 0.78757 -0.306754 369 | -1.77581 0.661075 -0.333198 370 | -1.76812 0.573803 -0.359594 371 | -1.77018 0.476768 -0.375318 372 | -1.72267 0.488582 -0.371959 373 | -1.83221 0.797361 -0.305126 374 | -1.85047 0.690416 -0.339012 375 | -1.8138 0.576973 -0.36267 376 | -1.79546 0.479611 -0.377697 377 | -1.86857 0.686409 -0.370208 378 | -1.84579 0.564648 -0.379527 379 | -1.82815 0.470733 -0.396709 380 | -1.81494 0.927047 -0.404133 381 | 0.509385 0.517291 -0.392288 382 | 0.533445 0.624065 -0.391587 383 | 0.550725 0.635517 -0.355498 384 | 0.545686 0.698743 -0.399473 385 | 0.560938 0.699523 -0.35701 386 | 0.549429 0.829496 -0.399936 387 | 0.563323 0.83699 -0.36148 388 | 0.555798 0.907171 -0.424207 389 | 0.566294 0.914995 -0.376516 390 | 0.424256 0.507823 -0.402687 391 | 0.412257 0.601623 -0.418543 392 | 0.398407 0.495427 -0.39097 393 | 0.416497 0.675089 -0.426059 394 | 0.385099 0.598189 -0.407553 395 | 0.415227 0.805586 -0.440491 396 | 0.374563 0.683142 -0.42255 397 | 0.385768 0.877725 -0.462205 398 | 0.351675 0.797625 -0.432436 399 | 0.38825 0.491993 -0.370041 400 | 0.357557 0.600953 -0.386217 401 | 0.332426 0.681035 -0.38903 402 | 0.337909 0.878726 -0.444942 403 | 0.32335 0.806005 -0.409752 404 | 0.391578 0.507404 -0.346457 405 | 0.364156 0.603871 -0.345103 406 | 0.338941 0.686043 -0.344543 407 | 0.310967 0.88026 -0.418167 408 | 0.307996 0.801434 -0.35034 409 | 0.432508 0.524847 -0.308838 410 | 0.397794 0.616734 -0.304823 411 | 0.382723 0.687868 -0.301847 412 | 0.298272 0.90815 -0.30766 413 | 0.362154 0.844157 -0.299682 414 | 0.519594 0.517865 -0.36401 415 | 0.512144 0.886744 -0.450519 416 | 0.514242 0.827658 -0.437564 417 | 0.479992 0.514462 -0.4103 418 | 0.504046 0.684747 -0.439248 419 | 0.452247 0.507968 -0.411618 420 | 0.453921 0.905901 -0.478008 421 | 0.460058 0.828751 -0.449087 422 | 0.469041 0.673458 -0.437961 423 | 0.459802 0.583277 -0.424868 424 | 0.498637 0.597188 -0.423211 425 | 0.417018 0.902274 -0.263214 426 | 0.363539 0.89992 -0.272585 427 | 0.425446 0.862759 -0.29062 428 | 0.428682 0.691862 -0.279485 429 | 0.516667 0.526244 -0.320811 430 | 0.464383 0.511204 -0.29475 431 | 0.505475 0.652144 -0.303218 432 | 0.439847 0.620111 -0.282174 433 | 0.523672 0.902869 -0.268032 434 | 0.536341 0.832533 -0.285625 435 | 0.515759 0.714673 -0.294419 436 | 0.602189 1.059 -0.41279 437 | 0.583802 1.04782 -0.463268 438 | 0.589088 0.996277 -0.393095 439 | 0.525231 1.06186 -0.506449 440 | 0.571406 0.98165 -0.441417 441 | 0.454045 1.04411 -0.511563 442 | 0.528546 0.955603 -0.469082 443 | 0.364344 1.04678 -0.501027 444 | 0.452542 0.957251 -0.495676 445 | 0.318394 1.0376 -0.477593 446 | 0.369052 0.948321 -0.48265 447 | 0.28901 1.02966 -0.449672 448 | 0.326866 0.962726 -0.468891 449 | 0.2526 1.0381 -0.370449 450 | 0.299589 0.972786 -0.428359 451 | 0.618132 1.10611 -0.427412 452 | 0.605397 1.117 -0.467521 453 | 0.550798 1.12953 -0.514715 454 | 0.468896 1.12399 -0.527472 455 | 0.383784 1.12389 -0.515288 456 | 0.330265 1.1072 -0.501392 457 | 0.292369 1.09718 -0.481917 458 | 0.236135 1.10234 -0.401148 459 | 0.63781 1.18124 -0.444921 460 | 0.379076 1.17777 -0.520225 461 | 0.481574 1.19742 -0.529905 462 | 0.565561 1.19275 -0.510769 463 | 0.609818 1.18192 -0.488786 464 | 0.288159 1.1683 -0.497716 465 | 0.335392 1.16866 -0.520501 466 | 0.984735 2.47235 -0.0129634 467 | 0.974274 2.47723 0.00212119 468 | 1.08979 2.51719 0.00212077 469 | 0.996751 2.44695 -0.0727462 470 | 1.08386 2.51096 -0.0298071 471 | 1.00645 2.38495 -0.12895 472 | 1.0919 2.49648 -0.0632118 473 | 1.01892 2.32309 -0.147252 474 | 1.10253 2.42482 -0.127597 475 | 1.03158 2.26111 -0.165489 476 | 1.12951 2.37419 -0.147847 477 | 1.05265 2.13662 -0.201728 478 | 1.14701 2.30317 -0.174547 479 | 1.06433 2.00328 -0.218337 480 | 1.1894 2.20546 -0.198298 481 | 1.10445 1.82841 -0.218033 482 | 1.21366 2.07056 -0.213631 483 | 1.12258 1.72081 -0.203187 484 | 1.22731 1.91468 -0.197365 485 | 1.13943 1.6762 -0.179797 486 | 1.25387 1.81133 -0.170563 487 | 1.1477 1.63575 -0.154526 488 | 1.26337 1.78286 -0.157542 489 | 1.17421 1.56684 -0.111172 490 | 1.27814 1.75261 -0.133579 491 | 1.20773 1.54952 -0.0805714 492 | 1.28945 1.72041 -0.10401 493 | 1.19498 1.54079 0.00212038 494 | 1.3056 1.6834 -0.0758242 495 | 1.30123 2.62082 -0.0640237 496 | 1.18274 2.55172 -0.0431332 497 | 1.18128 2.55975 0.00212043 498 | 1.47733 1.88626 0.00211933 499 | 1.39035 1.78472 0.00211966 500 | 1.40197 1.79386 -0.0849802 501 | 1.4748 1.8797 -0.0796335 502 | 1.37288 1.81275 -0.106919 503 | 1.36063 1.85038 -0.135395 504 | 1.4679 1.89973 -0.130124 505 | 1.35513 1.89614 -0.168562 506 | 1.45161 1.95542 -0.174561 507 | 1.34357 1.97928 -0.201323 508 | 1.43989 2.06158 -0.216928 509 | 1.31033 2.12558 -0.226511 510 | 1.41646 2.17533 -0.235715 511 | 1.26768 2.24848 -0.208861 512 | 1.3713 2.28657 -0.220415 513 | 1.24103 2.35311 -0.17949 514 | 1.36951 2.38103 -0.207856 515 | 1.21928 2.41839 -0.168196 516 | 1.33993 2.47094 -0.193159 517 | 1.19205 2.47528 -0.137829 518 | 1.31495 2.57597 -0.140284 519 | 1.18358 2.53049 -0.0773887 520 | 1.30942 2.60212 -0.104525 521 | 1.13155 1.43368 -0.0866367 522 | 1.12849 1.43761 0.00212062 523 | 0.689612 2.4001 0.00212225 524 | 0.858843 2.44028 0.00212162 525 | 0.855409 2.40915 -0.0718068 526 | 0.699085 2.38201 -0.0871817 527 | 0.865292 2.34704 -0.127939 528 | 0.719309 2.32853 -0.148406 529 | 0.88184 2.28153 -0.153409 530 | 0.768705 2.25826 -0.184323 531 | 0.899335 2.2105 -0.180109 532 | 0.784063 2.16937 -0.223723 533 | 0.916492 2.08547 -0.215925 534 | 0.820911 2.05167 -0.254258 535 | 0.957972 1.94856 -0.224923 536 | 0.869611 1.91721 -0.269272 537 | 1.00765 1.77835 -0.250988 538 | 0.936086 1.72311 -0.284979 539 | 0.897634 1.81003 -0.287685 540 | 1.04081 1.67873 -0.235873 541 | 0.9454 1.64066 -0.281082 542 | 1.05396 1.61264 -0.199444 543 | 0.960017 1.54696 -0.227321 544 | 1.06869 1.53548 -0.165453 545 | 1.10698 1.47067 -0.119688 546 | 1.30327 1.68541 0.00211998 547 | 0.83942 1.90627 -0.315513 548 | 0.871912 1.77994 -0.312238 549 | 0.888452 1.69987 -0.314495 550 | 0.867875 1.54601 -0.314504 551 | 0.888443 1.62278 -0.314156 552 | 0.766563 2.03908 -0.295218 553 | 0.752788 2.04302 -0.307517 554 | 0.714631 2.15084 -0.26136 555 | 0.779438 1.36167 -0.410997 556 | 0.801973 1.41681 -0.430428 557 | 0.844327 1.441 -0.359052 558 | 0.807672 1.51145 -0.427325 559 | 0.849616 1.51623 -0.348592 560 | 0.826182 1.61714 -0.449621 561 | 0.86355 1.62034 -0.379537 562 | 0.834786 1.69413 -0.445023 563 | 0.862373 1.69978 -0.390896 564 | 0.811451 1.80061 -0.421387 565 | 0.851547 1.77675 -0.372382 566 | 0.79135 1.92886 -0.363927 567 | 0.806258 1.92452 -0.337157 568 | 0.779025 2.04403 -0.283784 569 | 0.596398 2.39159 0.00212259 570 | 0.598271 2.37723 -0.0773424 571 | 0.620585 2.33238 -0.148533 572 | 0.672754 2.21938 -0.23857 573 | 0.648187 1.22222 -0.436829 574 | 0.692466 1.27469 -0.444552 575 | 0.570496 2.36489 -0.0916598 576 | 0.582477 2.34314 -0.141938 577 | 0.623599 2.25079 -0.225997 578 | 0.657171 2.16451 -0.290281 579 | 0.693014 2.0732 -0.332348 580 | 0.715967 1.948 -0.401344 581 | 0.737821 1.83681 -0.455149 582 | 0.75827 1.71368 -0.496911 583 | 0.760532 1.58781 -0.513706 584 | 0.739417 1.49566 -0.499873 585 | 0.733792 1.42895 -0.496576 586 | 0.709464 1.34232 -0.45767 587 | 0.545879 1.3113 -0.523099 588 | 0.587923 1.44582 -0.553162 589 | 0.455096 2.37755 -0.0761781 590 | 0.449312 2.39129 0.00212313 591 | 0.59998 1.52052 -0.56126 592 | 0.602413 1.57887 -0.568979 593 | 0.575925 1.72811 -0.553061 594 | 0.550243 1.83659 -0.502341 595 | 0.529305 1.96822 -0.446808 596 | 0.521512 2.10148 -0.377772 597 | 0.477955 2.24259 -0.276567 598 | 0.461425 2.31657 -0.175855 599 | 0.451186 2.35899 -0.112201 600 | -0.243122 2.3456 -0.0687302 601 | -0.238326 2.3659 0.00212567 602 | -0.0182335 2.37064 0.00212486 603 | -0.237092 2.30667 -0.125123 604 | -0.016431 2.3104 -0.122056 605 | -0.214298 2.26289 -0.187445 606 | -0.021699 2.25479 -0.201441 607 | -0.206968 2.1756 -0.275462 608 | -0.00637241 2.13444 -0.306685 609 | -0.234382 2.10316 -0.359335 610 | 0.0362096 2.03745 -0.383157 611 | -0.202265 1.94942 -0.476709 612 | 0.0644169 1.93635 -0.438391 613 | -0.104 1.75928 -0.550868 614 | 0.0723291 1.77075 -0.52062 615 | -0.104048 1.6686 -0.580191 616 | 0.0672642 1.6893 -0.541412 617 | -0.113865 1.59412 -0.595892 618 | 0.0771559 1.62209 -0.551617 619 | -0.10262 1.52027 -0.601954 620 | 0.0743524 1.55867 -0.559808 621 | -0.100641 1.43092 -0.598806 622 | 0.0816081 1.46746 -0.54586 623 | -0.0989746 1.32421 -0.584731 624 | 0.0878722 1.3717 -0.500555 625 | -0.109082 1.22289 -0.550568 626 | 0.0765391 1.32176 -0.484072 627 | -0.101544 1.10375 -0.4814 628 | 0.0726424 1.20884 -0.447418 629 | -0.107803 1.02295 -0.407759 630 | 0.0799072 1.13135 -0.403888 631 | -0.104219 0.98232 -0.335056 632 | 0.0685344 1.06699 -0.364277 633 | 0.0650301 1.03194 -0.318922 634 | 0.0606178 0.961836 -0.251862 635 | 0.0607459 0.94233 -0.182817 636 | -0.588431 2.35006 -0.0799123 637 | -0.582939 2.37119 0.00212695 638 | -0.442611 2.36773 0.00212643 639 | -0.587514 2.32674 -0.117536 640 | -0.439353 2.34661 -0.0646124 641 | -0.617874 2.30212 -0.193214 642 | -0.459419 2.32047 -0.115385 643 | -0.605218 2.25989 -0.280455 644 | -0.451032 2.29318 -0.16941 645 | -0.639103 2.19085 -0.333357 646 | -0.420854 2.25181 -0.2379 647 | -0.743113 2.13404 -0.367157 648 | -0.426584 2.17874 -0.306477 649 | -0.768888 2.0005 -0.503138 650 | -0.520747 2.0463 -0.42594 651 | -0.673382 1.79638 -0.644697 652 | -0.392488 1.80532 -0.591294 653 | -0.626251 1.68227 -0.696259 654 | -0.339269 1.67533 -0.646862 655 | -0.578322 1.53957 -0.739418 656 | -0.333737 1.60451 -0.669317 657 | -0.576894 1.34657 -0.747873 658 | -0.326684 1.50404 -0.678023 659 | -0.564339 1.20042 -0.723276 660 | -0.337087 1.38182 -0.692724 661 | -0.556479 1.07713 -0.660866 662 | -0.332432 1.23652 -0.664182 663 | -0.572798 0.986433 -0.576667 664 | -0.360036 1.09903 -0.612885 665 | -0.573631 0.944234 -0.512626 666 | -0.373423 1.00948 -0.543325 667 | -0.373582 0.963961 -0.477212 668 | -0.877541 2.37779 -0.0567158 669 | -0.861632 2.39082 0.00212798 670 | -0.723509 2.37672 0.00212747 671 | -0.882853 2.35663 -0.119549 672 | -0.735852 2.3582 -0.0648361 673 | -0.911569 2.33345 -0.224462 674 | -0.762635 2.34273 -0.127043 675 | -0.931727 2.3146 -0.317654 676 | -0.79035 2.31199 -0.236778 677 | -0.960538 2.27904 -0.395849 678 | -0.802829 2.26847 -0.333356 679 | -1.02564 2.22039 -0.460806 680 | -0.833475 2.21702 -0.359169 681 | -1.02625 2.10077 -0.505262 682 | -0.905463 2.12872 -0.415249 683 | -0.982884 1.98897 -0.543974 684 | -0.871019 2.03472 -0.484258 685 | -0.96135 1.8562 -0.593928 686 | -0.847727 1.9594 -0.550733 687 | -0.993926 1.73361 -0.632656 688 | -0.835733 1.79016 -0.640129 689 | -0.998387 1.59257 -0.663932 690 | -0.816597 1.67598 -0.682623 691 | -0.956863 1.29525 -0.682566 692 | -0.806076 1.45225 -0.742953 693 | -0.948342 1.18502 -0.637758 694 | -0.816558 1.2199 -0.717778 695 | -0.959882 1.10608 -0.574916 696 | -0.809531 1.09989 -0.657427 697 | -0.962219 1.05839 -0.488464 698 | -0.783122 1.01437 -0.594439 699 | 0.383061 1.22509 -0.530593 700 | 0.381262 1.30589 -0.54748 701 | 0.300402 2.39048 0.00212368 702 | 0.302981 2.37267 -0.0959082 703 | 0.312383 2.35156 -0.125173 704 | 0.318245 2.31689 -0.17469 705 | 0.321688 2.25718 -0.256182 706 | 0.327057 2.19145 -0.324552 707 | 0.355744 1.94315 -0.468741 708 | 0.350666 2.01687 -0.433887 709 | 0.376846 1.78849 -0.51467 710 | 0.385199 1.70219 -0.532127 711 | 0.390193 1.61179 -0.547128 712 | 0.391868 1.51964 -0.556265 713 | 0.398247 1.42249 -0.567043 714 | 0.183754 1.0167 -0.297059 715 | 0.24407 1.00699 -0.332333 716 | 0.191918 0.959636 -0.252153 717 | 0.226694 0.921489 0.00212396 718 | 0.197586 0.927634 -0.189417 719 | 0.365766 0.916904 0.00212344 720 | 0.195713 1.06619 -0.360677 721 | 0.210607 1.19381 -0.43941 722 | 0.263619 1.35436 -0.485523 723 | 0.248041 1.18636 -0.448076 724 | 0.20054 1.12477 -0.392199 725 | 0.0671428 0.916247 0.00212455 726 | -0.761592 0.968223 -0.513026 727 | -0.943831 2.38331 -0.0568963 728 | -0.937223 2.3998 0.00212826 729 | -0.957227 2.36311 -0.115851 730 | -0.9666 2.34212 -0.231176 731 | -0.987688 2.33293 -0.316194 732 | -1.03916 2.29423 -0.430902 733 | -1.1007 2.21653 -0.48863 734 | -1.10595 2.08102 -0.518685 735 | -1.13844 1.89292 -0.530997 736 | -1.13348 1.80266 -0.546081 737 | -1.13999 1.73002 -0.567513 738 | -1.13303 1.61799 -0.602293 739 | -1.13643 1.4787 -0.615588 740 | -1.15186 1.36483 -0.569096 741 | -1.12764 1.26347 -0.515216 742 | -1.11647 1.18653 -0.472109 743 | -1.08398 2.39188 -0.0514297 744 | -1.08073 2.40856 0.00212879 745 | -1.09745 2.37376 -0.107011 746 | -1.11081 2.36799 -0.189099 747 | -1.19236 2.31612 -0.353337 748 | -1.22162 2.21504 -0.466938 749 | -1.21469 2.10314 -0.501806 750 | -1.22936 1.96062 -0.508696 751 | -1.23664 1.84464 -0.52233 752 | -1.23266 1.78485 -0.542131 753 | -1.19376 1.70594 -0.572949 754 | -1.17811 1.61993 -0.599931 755 | -1.20153 1.48177 -0.604881 756 | -1.23817 1.37138 -0.561069 757 | -1.24551 1.27018 -0.489009 758 | -1.24255 1.21717 -0.451413 759 | -1.23806 1.2021 -0.42291 760 | -1.25842 2.40454 -0.05887 761 | -1.24862 2.41492 0.00212941 762 | -1.26749 2.39229 -0.0989264 763 | -1.28396 2.37607 -0.188803 764 | -1.29922 2.31869 -0.352864 765 | -1.31405 2.20099 -0.474678 766 | -1.35384 2.07174 -0.514121 767 | -1.35481 1.94193 -0.528553 768 | -1.33631 1.84451 -0.543726 769 | -1.29316 1.77143 -0.559005 770 | -1.25437 1.69483 -0.586401 771 | -1.25189 1.61153 -0.620238 772 | -1.30604 1.43774 -0.618047 773 | -1.34515 1.29917 -0.556831 774 | -1.35208 1.19157 -0.495166 775 | -1.35529 1.15122 -0.458381 776 | -1.35851 1.11087 -0.421595 777 | -1.51996 2.44304 -0.0274789 778 | -1.5008 2.44881 0.00213034 779 | -1.53074 2.42813 -0.094319 780 | -1.53327 2.40792 -0.172047 781 | -1.53862 2.37324 -0.264405 782 | -1.53961 2.29832 -0.384006 783 | -1.52526 2.15956 -0.487385 784 | -1.4756 1.97154 -0.549849 785 | -1.45966 1.8927 -0.55755 786 | -1.45297 1.84967 -0.559296 787 | -1.43217 1.7359 -0.578286 788 | -1.41437 1.63773 -0.602341 789 | -1.40615 1.55547 -0.612969 790 | -1.39213 1.41923 -0.604007 791 | -1.4131 1.24076 -0.550863 792 | -1.47316 1.06929 -0.51234 793 | -1.68755 2.47112 -0.0203944 794 | -1.68069 2.48554 0.002131 795 | -1.69838 2.42805 -0.0936879 796 | -1.69734 2.41698 -0.15795 797 | -1.71221 2.39207 -0.247068 798 | -1.7019 2.33382 -0.343676 799 | -1.6769 2.2475 -0.412813 800 | -1.63343 2.08972 -0.494169 801 | -1.58737 1.93646 -0.530827 802 | -1.57185 1.8099 -0.537541 803 | -1.57026 1.71984 -0.543306 804 | -1.52618 1.63709 -0.566762 805 | -1.50957 1.49669 -0.588398 806 | -1.49508 1.37783 -0.590377 807 | -1.49878 1.21172 -0.553812 808 | -1.54326 1.06772 -0.522602 809 | -1.89324 2.34611 -0.137662 810 | -1.88793 2.35272 0.00213177 811 | -1.83729 2.3832 0.00213158 812 | -1.89652 2.30128 -0.223863 813 | -1.82218 2.40123 -0.16542 814 | -1.89028 2.24156 -0.267375 815 | -1.83843 2.36423 -0.242417 816 | -1.87407 2.17092 -0.308538 817 | -1.81347 2.30807 -0.301869 818 | -1.85905 2.09055 -0.334176 819 | -1.78673 2.23467 -0.374304 820 | -1.83127 1.94175 -0.388426 821 | -1.77204 2.13025 -0.399426 822 | -1.79942 1.77063 -0.433222 823 | -1.75073 1.95482 -0.432469 824 | -1.77487 1.68042 -0.462237 825 | -1.71376 1.80486 -0.47607 826 | -1.73477 1.59494 -0.488769 827 | -1.68382 1.70213 -0.511383 828 | -1.70872 1.44686 -0.510272 829 | -1.6516 1.61737 -0.533882 830 | -1.70658 1.30874 -0.500429 831 | -1.62319 1.45091 -0.562795 832 | -1.71795 1.16301 -0.467337 833 | -1.62058 1.33016 -0.563897 834 | -1.73036 1.04801 -0.43913 835 | -1.63666 1.16122 -0.535398 836 | -1.74744 0.982462 -0.422639 837 | -1.65651 1.04578 -0.497572 838 | -1.98814 2.30388 -0.127995 839 | -1.9686 2.30946 0.00213207 840 | -1.97182 2.24978 -0.188929 841 | -1.96594 2.19865 -0.218904 842 | -1.95294 2.12823 -0.250757 843 | -1.94621 2.05075 -0.269055 844 | -1.92108 1.92699 -0.305461 845 | -1.88655 1.78203 -0.371266 846 | -1.85116 1.67318 -0.402656 847 | -1.82522 1.55324 -0.417696 848 | -1.79215 1.41623 -0.431693 849 | -1.767 1.30183 -0.445517 850 | -1.7691 1.17153 -0.421766 851 | -1.78648 1.08426 -0.401343 852 | -1.97701 2.19887 -0.0912052 853 | -1.97703 2.22821 0.0021321 854 | -1.97343 2.16424 -0.117094 855 | -1.97089 2.11326 -0.13753 856 | -1.96056 2.06355 -0.15876 857 | -1.957 2.01446 -0.161299 858 | -1.94243 1.91226 -0.183132 859 | -1.91558 1.77321 -0.229065 860 | -1.89345 1.66503 -0.270536 861 | -1.86615 1.54773 -0.320414 862 | -1.84339 1.45185 -0.326916 863 | -1.7892 1.28103 -0.347829 864 | -1.42736 1.02777 -0.42387 865 | -1.48401 0.937248 -0.388195 866 | 0.558519 2.38663 0.00212273 867 | -1.58109 0.810576 -0.312053 868 | -1.80535 0.356845 -0.466851 869 | -1.77956 0.359688 -0.477568 870 | -1.76257 0.280029 -0.494301 871 | -1.72633 0.375461 -0.452927 872 | -1.68762 0.384444 -0.457639 873 | -1.65812 0.310009 -0.47733 874 | -1.67138 0.384365 -0.423988 875 | -1.64057 0.307558 -0.432659 876 | -1.79746 0.272915 -0.495328 877 | -1.79721 0.24785 -0.489315 878 | -1.76451 0.218369 -0.484511 879 | -1.80369 0.206348 -0.492119 880 | -1.61333 0.252646 -0.435934 881 | -1.62404 0.243574 -0.477978 882 | -1.74221 0.289934 -0.499988 883 | -1.75077 0.374191 -0.458706 884 | -1.80979 0.19918 -0.416665 885 | -1.79392 0.207538 -0.369393 886 | -1.77732 0.266651 -0.372422 887 | -1.79655 0.370858 -0.385332 888 | -1.81386 0.348329 -0.423855 889 | -1.81136 0.254952 -0.427549 890 | -1.67792 0.238523 -0.48556 891 | -1.71136 0.303816 -0.479336 892 | -1.71778 0.227776 -0.498833 893 | -1.73888 0.221181 -0.495214 894 | -1.66785 0.325001 -0.396644 895 | -1.63271 0.248683 -0.405518 896 | -1.73775 0.279593 -0.355856 897 | -1.69492 0.312218 -0.37046 898 | -1.72471 0.379357 -0.369966 899 | -1.74561 0.383056 -0.372616 900 | -1.68179 0.377396 -0.401039 901 | -1.77488 1.18526 -0.359277 902 | -1.91901 1.97252 -0.125042 903 | -1.90948 1.91396 -0.121573 904 | -1.90071 1.79821 -0.139809 905 | -1.89198 1.66893 -0.187575 906 | -1.87167 1.56877 -0.238727 907 | -1.92821 1.95422 0.00213192 908 | -1.92935 2.17324 0.00213192 909 | -1.93241 2.11616 0.00213193 910 | -1.93846 2.04643 0.00213196 911 | -2.05529 2.04576 -0.0232759 912 | -2.03639 1.82284 -0.021288 913 | -2.04176 1.82224 0.00213234 914 | -2.0436 2.25552 -0.0252597 915 | -2.06112 2.04516 0.00213241 916 | -1.97224 2.39139 -0.0272435 917 | -2.04991 2.25581 0.00213237 918 | -1.8712 2.4679 -0.0292276 919 | -1.97836 2.39428 0.0021321 920 | -1.76916 2.48725 -0.0312116 921 | -1.87503 2.47403 0.00213172 922 | -2.03937 2.0474 -0.0418738 923 | -2.02173 1.8245 -0.0384355 924 | -2.02636 2.25476 -0.0453122 925 | -1.95549 2.3835 -0.0487508 926 | -1.8607 2.45115 -0.0521894 927 | -1.76443 2.468 -0.0556281 928 | -2.01761 2.04964 -0.0486889 929 | -2.00169 1.82677 -0.0447172 930 | -2.0028 2.25372 -0.0526606 931 | -1.93261 2.37272 -0.0566282 932 | -1.84637 2.42827 -0.0606002 933 | -1.99584 2.05188 -0.0418916 934 | -1.98165 1.82903 -0.0384489 935 | -1.97923 2.25267 -0.04533 936 | -1.90972 2.36194 -0.0487686 937 | -1.83202 2.40539 -0.0522072 938 | -1.97989 2.05352 -0.0232983 939 | -1.96697 1.83069 -0.0213146 940 | -1.96197 2.2519 -0.0252864 941 | -1.89296 2.35404 -0.0272747 942 | -1.82152 2.38863 -0.029263 943 | -1.97405 2.05413 0.00210123 944 | -1.96158 1.8313 0.00210559 945 | -1.95564 2.25162 0.00210116 946 | -1.81766 2.38249 0.00209184 947 | -1.77088 2.4943 0.00213134 948 | 1.80134 2.42054 -0.270343 949 | 1.79308 2.49427 -0.279133 950 | 1.83408 2.50764 -0.250401 951 | 1.8587 2.4892 -0.228519 952 | 1.83797 2.41463 -0.251512 953 | 1.85869 2.41623 -0.227439 954 | 1.82179 2.39496 -0.257026 955 | 1.79736 2.40381 -0.26374 956 | 1.84627 2.38928 -0.24188 957 | 1.85486 2.3995 -0.220835 958 | 1.86738 2.43002 -0.20207 959 | 1.84689 2.50848 -0.218243 960 | 1.87119 2.47524 -0.209903 961 | 1.78564 2.52418 -0.251824 962 | 1.81014 2.52656 -0.235898 963 | 1.75695 2.43257 -0.268152 964 | 1.7691 2.49723 -0.266168 965 | 1.77343 2.53697 -0.258441 966 | 1.80615 2.55507 -0.237194 967 | 1.83055 2.55388 -0.225596 968 | 1.8264 2.52221 -0.232706 969 | 1.86341 2.53148 -0.204283 970 | 1.88769 2.48608 -0.197115 971 | 1.89584 2.44123 -0.193509 972 | 1.87569 2.40879 -0.192192 973 | 1.85877 2.37944 -0.222868 974 | 1.83416 2.36923 -0.243537 975 | 1.80555 2.3708 -0.258988 976 | 1.78131 2.39576 -0.264145 977 | 1.90438 2.46778 -0.174877 978 | 1.90017 2.43572 -0.177878 979 | 1.88799 2.3915 -0.181872 980 | 1.87109 2.37022 -0.211922 981 | 1.82619 2.34446 -0.237771 982 | 1.80179 2.34563 -0.249215 983 | 1.75317 2.36294 -0.258534 984 | 1.72904 2.38263 -0.25208 985 | 1.87585 2.52992 -0.188458 986 | 1.89197 2.49708 -0.184032 987 | 1.83499 2.56472 -0.212531 988 | 1.77762 2.54819 -0.249316 989 | 1.75281 2.50235 -0.277414 990 | 1.74287 2.5008 -0.268677 991 | 1.74877 2.43295 -0.271912 992 | 1.72486 2.50531 -0.26436 993 | 1.79063 2.58876 -0.209176 994 | 1.81026 2.57062 -0.23164 995 | 1.81555 2.58208 -0.182013 996 | 1.86057 2.55045 -0.149755 997 | 1.88916 2.50838 -0.134234 998 | 1.90513 2.46468 -0.142816 999 | 1.90889 2.42495 -0.150892 1000 | 1.72879 2.42429 -0.264154 1001 | 1.74748 2.61675 -0.160978 1002 | 1.78868 2.60068 -0.12298 1003 | 1.84973 2.54953 -0.0969675 1004 | 1.89415 2.5041 -0.090113 1005 | 1.91839 2.45964 -0.090986 1006 | 1.92965 2.41022 -0.124412 1007 | 1.92104 2.35948 -0.145228 1008 | 1.90793 2.3193 -0.189317 1009 | 1.85477 2.26582 -0.221642 1010 | 1.83029 2.25871 -0.229894 1011 | 1.77348 2.25263 -0.249418 1012 | 1.737 2.26543 -0.255466 1013 | 1.69281 2.32602 -0.252568 1014 | 1.66871 2.39016 -0.245806 1015 | 1.65653 2.48002 -0.253102 1016 | 1.66463 2.41511 -0.251431 1017 | 1.74951 2.56392 -0.242999 1018 | 1.66896 2.54352 -0.239115 1019 | 1.88425 2.4993 0.00214869 1020 | 1.93139 2.4597 -0.0507753 1021 | 1.9588 2.39827 -0.0857404 1022 | 1.95793 2.3247 -0.121221 1023 | 1.96513 2.2391 -0.157892 1024 | 1.72089 2.23732 -0.257811 1025 | 1.68446 2.27019 -0.261918 1026 | 1.6684 2.31032 -0.257664 1027 | 1.63214 2.34727 -0.261226 1028 | 1.62416 2.3874 -0.257162 1029 | 1.61223 2.43147 -0.252621 1030 | 1.75126 2.61718 0.00199489 1031 | 1.70144 2.64758 -0.0596479 1032 | 1.70215 2.60097 -0.205944 1033 | 1.62975 2.62819 -0.193495 1034 | 1.67613 2.65658 -0.110817 1035 | 1.59322 2.56881 -0.206526 1036 | 1.61241 2.49576 -0.246406 1037 | 1.96072 2.20781 -0.168948 1038 | 1.93213 2.14843 -0.182159 1039 | 1.84266 2.14841 -0.220593 1040 | 1.75725 2.20408 -0.249748 1041 | 2.0039 2.39475 -0.050608 1042 | 1.94062 2.45503 0.00221019 1043 | 2.0291 2.3828 0.00231125 1044 | 2.04938 2.36195 0.00233763 1045 | 2.04828 2.34617 -0.052345 1046 | 2.03126 2.31721 -0.0871248 1047 | 2.02682 2.2826 -0.106636 1048 | 2.00972 2.22158 -0.144514 1049 | 1.99325 2.18619 -0.155684 1050 | 1.97724 2.12524 -0.153074 1051 | 1.97276 2.09829 -0.167696 1052 | 1.85869 2.11595 -0.220117 1053 | 1.74493 2.14428 -0.25923 1054 | 1.70433 2.16987 -0.272079 1055 | 1.65174 2.21962 -0.282156 1056 | 1.61152 2.28022 -0.279511 1057 | 1.59971 2.33606 -0.26969 1058 | 1.59185 2.38387 -0.2609 1059 | 2.12189 2.29701 0.00242111 1060 | 2.12898 2.28478 -0.0480342 1061 | 2.11199 2.26388 -0.0820382 1062 | 2.09517 2.23809 -0.108381 1063 | 2.07037 2.19622 -0.136254 1064 | 2.05003 2.16059 -0.143214 1065 | 2.03777 2.12086 -0.150756 1066 | 2.03358 2.0967 -0.152996 1067 | 2.18933 2.24857 -0.0529362 1068 | 2.18432 2.23611 -0.0903875 1069 | 2.16438 2.24339 -0.0810862 1070 | 2.17539 2.20304 -0.125749 1071 | 2.13078 2.18418 -0.138819 1072 | 2.14763 2.218 -0.111537 1073 | 2.16285 2.16859 -0.145057 1074 | 2.11063 2.14778 -0.137726 1075 | 2.15865 2.11668 -0.153965 1076 | 2.11836 2.12082 -0.15263 1077 | 2.16519 2.2643 -0.0467118 1078 | 2.07377 2.09312 -0.158422 1079 | 2.2657 2.21252 -0.0581953 1080 | 2.25327 2.21407 -0.0738617 1081 | 2.22082 2.22725 -0.0839561 1082 | 2.2869 2.17973 0.00253643 1083 | 2.29405 2.18756 -0.0531349 1084 | 2.27732 2.18989 -0.0767623 1085 | 2.23065 2.23638 0.00253664 1086 | 2.23355 2.2326 -0.0555063 1087 | 2.28708 2.1465 0.00253643 1088 | 2.27103 2.10189 0.00253649 1089 | 2.28626 2.09298 -0.0376977 1090 | 2.26295 2.07355 0.00253652 1091 | 2.27432 2.06821 -0.0318437 1092 | 2.26957 2.0552 -0.0653629 1093 | 2.28141 2.08052 -0.075312 1094 | 2.24045 2.04274 -0.102254 1095 | 2.19528 2.04589 -0.133437 1096 | 2.1991 2.07144 -0.147159 1097 | 2.2524 2.07148 -0.107883 1098 | 2.21533 2.0787 -0.1387 1099 | 2.16656 2.08502 -0.161358 1100 | 2.16257 2.06828 -0.15475 1101 | 2.12607 2.08582 -0.168472 1102 | 2.06986 2.04828 -0.154534 1103 | 2.11811 2.06498 -0.162173 1104 | 2.15874 2.04745 -0.148543 1105 | 2.11833 2.04376 -0.15211 1106 | 2.09826 2.03532 -0.148314 1107 | 2.04984 2.05991 -0.148958 1108 | 2.05392 2.03101 -0.143712 1109 | 2.07422 2.01822 -0.13729 1110 | 2.02961 2.06425 -0.152057 1111 | 2.02575 2.03536 -0.146626 1112 | 2.02705 1.99353 -0.0899416 1113 | 2.10318 2.00705 -0.106666 1114 | 2.08784 1.9839 -0.0761753 1115 | 2.14374 2.00192 -0.0959856 1116 | 2.12831 1.97915 -0.0694443 1117 | 2.19234 2.00901 -0.0882936 1118 | 2.17295 1.97757 -0.0543643 1119 | 1.96878 2.0619 -0.16714 1120 | 1.96089 2.03261 -0.157509 1121 | 1.99415 2.00394 -0.112572 1122 | 1.94943 2.00985 -0.131214 1123 | 2.20653 1.99613 0.00253673 1124 | 2.21385 1.99117 -0.0297584 1125 | 2.23765 2.01276 -0.0443273 1126 | 2.16194 1.97331 0.0025369 1127 | 2.11305 1.97117 -0.0293525 1128 | 2.11769 1.97255 0.00253706 1129 | 2.06034 1.97685 -0.0436875 1130 | 1.95644 1.98092 0.00236883 1131 | 1.91197 1.97383 0.00232932 1132 | 1.92277 1.9667 -0.0617293 1133 | 2.01966 1.97843 -0.0588556 1134 | 1.9789 1.98039 -0.0779734 1135 | 2.00484 1.98501 0.00240832 1136 | 1.97157 1.9773 -0.0457325 1137 | 2.06938 1.97296 0.00253724 1138 | 1.93011 1.96981 -0.0941333 1139 | 1.82746 1.96133 0.0022591 1140 | 1.84626 1.95474 -0.0611119 1141 | 1.86089 1.96055 -0.121649 1142 | 1.71674 1.92864 -0.0808863 1143 | 1.71047 1.93739 0.00216255 1144 | 1.86438 2.00378 -0.150081 1145 | 1.73542 1.9429 -0.144844 1146 | 1.87171 2.02259 -0.176662 1147 | 1.86723 2.07349 -0.20002 1148 | 1.74916 2.07016 -0.246244 1149 | 1.74988 2.02243 -0.214355 1150 | 1.7428 1.9906 -0.176763 1151 | 1.67187 2.11009 -0.281093 1152 | 1.64026 2.05488 -0.253327 1153 | 1.60512 2.00935 -0.200143 1154 | 1.59769 1.97814 -0.170617 1155 | 1.55284 2.00505 -0.19536 1156 | 1.58943 1.91383 0.00206161 1157 | 1.5798 1.912 -0.0713421 1158 | 1.5625 1.92548 -0.12625 1159 | 1.51691 1.97896 -0.176793 1160 | 1.58325 2.10186 -0.275848 1161 | 1.48377 2.04792 -0.217996 1162 | 1.54373 2.07833 -0.240688 1163 | 1.56854 2.02253 -0.21014 1164 | 1.49887 2.19849 -0.268534 1165 | 1.53074 2.21203 -0.284232 1166 | 1.56682 2.24895 -0.289473 1167 | 1.61946 2.15908 -0.283275 1168 | 1.55916 2.3453 -0.279974 1169 | 1.58776 2.42832 -0.26049 1170 | 1.55537 2.39667 -0.266948 1171 | 1.51931 2.33533 -0.259762 1172 | 1.47492 2.31491 -0.256721 1173 | 1.45925 2.1714 -0.237862 1174 | 1.52738 2.3835 -0.255293 1175 | 1.48716 2.37904 -0.250805 1176 | 1.45132 2.2965 -0.233714 1177 | 1.82369 2.55656 0.00207838 1178 | 2.1903 2.25686 0.00253679 1179 | 2.26297 2.21552 0.00253652 1180 | 1.56155 2.74447 0.00178841 1181 | 1.6221 2.71554 0.00185431 1182 | 1.62095 2.7161 -0.0552968 1183 | 1.57244 2.74106 -0.0597356 1184 | 1.61555 2.70992 -0.11653 1185 | 1.56792 2.7434 -0.0838039 1186 | 1.61103 2.7034 -0.133161 1187 | 1.50525 2.7524 0.00174013 1188 | 1.50407 2.74504 -0.0577605 1189 | 1.51116 2.74459 -0.0944889 1190 | 1.57123 2.74611 -0.112003 1191 | 1.51483 2.75047 -0.11426 1192 | 1.56638 2.73348 -0.149472 1193 | 1.60264 2.70534 -0.153033 1194 | 1.65433 2.69096 0.00188946 1195 | 1.63061 2.66932 -0.157168 1196 | 1.46048 2.71008 -0.197917 1197 | 1.45614 2.6664 -0.206027 1198 | 1.44084 2.65525 -0.174376 1199 | 1.44939 2.70954 -0.149074 1200 | 1.43729 2.66099 -0.149501 1201 | 1.45878 2.73656 -0.0940523 1202 | 1.45673 2.73686 0.00170064 1203 | 1.46639 2.73044 -0.115075 1204 | 1.46601 2.732 -0.131182 1205 | 1.47327 2.73547 -0.167373 1206 | 1.42158 2.67184 -0.135964 1207 | 1.43432 2.71372 -0.107809 1208 | 1.44589 2.7076 -0.128924 1209 | 1.41633 2.70071 0.00167434 1210 | 1.34571 2.64027 -0.100739 1211 | 1.40474 2.63816 -0.163074 1212 | 1.36447 2.61363 -0.160522 1213 | 1.43271 2.64325 -0.17535 1214 | 1.45572 2.6194 -0.222844 1215 | 1.40702 2.60858 -0.234878 1216 | 1.37917 2.59132 -0.223782 1217 | 1.3589 2.54727 -0.227573 1218 | 1.34366 2.54734 -0.186706 1219 | 1.47175 2.63216 -0.229955 1220 | 1.47104 2.61087 -0.260384 1221 | 1.42631 2.60399 -0.272131 1222 | 1.39017 2.58358 -0.269278 1223 | 1.37409 2.55074 -0.263949 1224 | 1.48592 2.60746 -0.309697 1225 | 1.44125 2.59704 -0.325936 1226 | 1.41745 2.57543 -0.311208 1227 | 1.39749 2.54222 -0.301837 1228 | 1.55235 2.59966 -0.230982 1229 | 1.51541 2.61851 -0.256686 1230 | 1.51501 2.60805 -0.273798 1231 | 1.52263 2.60588 -0.294437 1232 | 1.49742 2.61861 -0.341259 1233 | 1.45641 2.60129 -0.370371 1234 | 1.43242 2.56768 -0.356797 1235 | 1.54187 2.62175 -0.333854 1236 | 1.51649 2.63936 -0.388334 1237 | 1.46776 2.61638 -0.401545 1238 | 1.44785 2.57078 -0.389386 1239 | 1.46663 2.61709 -0.450091 1240 | 1.4901 2.65619 -0.479229 1241 | 1.46445 2.64647 -0.544482 1242 | 1.50715 2.66487 -0.442426 1243 | 1.5569 2.64686 -0.38456 1244 | 1.5389 2.67074 -0.462848 1245 | 1.52227 2.67663 -0.482143 1246 | 1.49667 2.68695 -0.545302 1247 | 1.46302 2.67273 -0.606654 1248 | 1.44723 2.61419 -0.587707 1249 | 1.44211 2.63534 -0.638171 1250 | 1.44243 2.57621 -0.445352 1251 | 1.44885 2.58713 -0.517323 1252 | 1.41687 2.53725 -0.33514 1253 | 1.43149 2.53911 -0.396056 1254 | 1.43048 2.54732 -0.439731 1255 | 1.43249 2.53185 -0.530424 1256 | 1.45811 2.56236 -0.637467 1257 | 1.46707 2.50187 -0.599033 1258 | 1.48861 2.42702 -0.537874 1259 | 1.43782 2.48142 -0.470676 1260 | 1.47791 2.40921 -0.47859 1261 | 1.40682 2.47133 -0.240013 1262 | 1.414 2.47931 -0.279915 1263 | 1.46302 2.43606 -0.252864 1264 | 1.44793 2.42336 -0.205101 1265 | 1.43542 2.47087 -0.402747 1266 | 1.42925 2.48318 -0.320399 1267 | 1.48778 2.40577 -0.402127 1268 | 1.56029 2.54753 -0.236205 1269 | 1.5726 2.53436 -0.225644 1270 | 1.55616 2.51098 -0.235659 1271 | 1.48718 2.65622 -0.604825 1272 | 1.46637 2.62254 -0.631838 1273 | 1.49621 2.61988 -0.563895 1274 | 1.48329 2.61533 -0.600558 1275 | 1.4788 2.62098 -0.616013 1276 | 1.48402 2.60828 -0.568881 1277 | 1.50866 2.65883 -0.5483 1278 | 1.5086 2.63877 -0.550235 1279 | 1.4874 2.63499 -0.594602 1280 | 1.50939 2.61916 -0.515631 1281 | 1.53937 2.53864 -0.268953 1282 | 1.5427 2.58186 -0.297227 1283 | 1.57776 2.53026 -0.351667 1284 | 1.58947 2.57643 -0.36773 1285 | 1.58452 2.61632 -0.40426 1286 | 1.55518 2.63788 -0.458268 1287 | 1.52991 2.65021 -0.500983 1288 | 1.51783 2.64216 -0.501481 1289 | 1.54293 2.62588 -0.459146 1290 | 1.55225 2.59233 -0.405834 1291 | 1.54895 2.56112 -0.376401 1292 | 1.5149 2.60939 -0.455945 1293 | 1.5441 2.47458 -0.234751 1294 | 1.54953 2.53439 -0.350614 1295 | 1.51974 2.58545 -0.417864 1296 | 1.50864 2.55719 -0.375846 1297 | 1.48905 2.52226 -0.350384 1298 | 1.48813 2.53025 -0.390097 1299 | 1.48715 2.55047 -0.432772 1300 | 1.48966 2.56883 -0.495799 1301 | 1.48878 2.58867 -0.53437 1302 | 1.47969 2.50724 -0.404247 1303 | 1.47443 2.51268 -0.460371 1304 | 1.47714 2.53818 -0.514741 1305 | 1.48024 2.56211 -0.553003 1306 | 1.49172 2.46278 -0.404838 1307 | 1.48221 2.46055 -0.46559 1308 | 1.48492 2.49092 -0.527467 1309 | 1.47588 2.52315 -0.568793 1310 | 1.4712 2.57087 -0.60043 1311 | 1.47087 2.58838 -0.614994 1312 | 1.55579 2.44367 -0.250131 1313 | 1.52395 2.44215 -0.233433 1314 | 1.54553 2.50944 -0.344799 1315 | 1.57799 2.51315 -0.341207 1316 | 1.52963 2.48863 -0.338469 1317 | 1.45541 2.37317 -0.230381 1318 | 1.29651 2.63624 0.00212 1319 | 1.3278 2.65948 0.00160855 1320 | 1.38734 2.47273 -0.211039 1321 | 0.720809 1.2603 0.372888 1322 | 0.66883 1.21893 0.391093 1323 | 0.641014 1.16565 0.382468 1324 | 0.777598 1.28243 0.332942 1325 | 0.71946 1.17347 0.357014 1326 | 0.821001 1.26462 0.282936 1327 | 0.76932 1.18236 0.32808 1328 | 0.766565 1.12818 0.313603 1329 | 0.834939 1.193 0.247728 1330 | 0.710274 1.11127 0.337742 1331 | 0.619268 1.10488 0.364386 1332 | 0.696088 1.07703 0.326202 1333 | 0.680439 1.0328 0.299167 1334 | 0.609583 1.07003 0.347692 1335 | 0.660933 0.971349 0.252225 1336 | 0.595561 1.01689 0.319952 1337 | 0.754385 1.04123 0.278872 1338 | 0.782064 1.01467 0.238026 1339 | 0.74139 0.985688 0.240102 1340 | 0.812321 1.05858 0.231449 1341 | 0.765097 1.09244 0.301018 1342 | 0.853206 1.23733 0.236849 1343 | 0.874026 1.11837 0.210044 1344 | 0.917984 1.19301 0.174566 1345 | 0.835371 1.11467 0.241932 1346 | 0.894211 1.04965 0.195343 1347 | 0.913443 1.11668 0.17946 1348 | 0.866506 1.0129 0.206482 1349 | 0.832184 0.968263 0.212896 1350 | 0.767072 0.938914 0.215157 1351 | 0.726068 0.937217 0.219957 1352 | 0.649971 0.945244 0.236312 1353 | 0.575002 0.953765 0.290854 1354 | 0.949334 1.11506 0.139676 1355 | 0.963145 1.18808 0.127637 1356 | 0.933601 1.02924 0.148492 1357 | 0.9033 0.982911 0.158614 1358 | 0.8578 0.933029 0.161863 1359 | 0.78027 0.900903 0.172411 1360 | 0.714743 0.900929 0.174025 1361 | 0.647251 0.904658 0.192173 1362 | 0.56116 0.905893 0.247139 1363 | 0.908184 1.50137 0.256862 1364 | 0.864438 1.45062 0.29277 1365 | 0.928299 1.38586 0.232211 1366 | 0.974734 1.42097 0.191211 1367 | 0.941391 1.32181 0.192194 1368 | 0.90382 1.35305 0.245714 1369 | 0.843249 1.37512 0.298779 1370 | 0.825281 1.33367 0.297236 1371 | 0.812471 1.3612 0.357191 1372 | 0.977674 1.29096 0.153143 1373 | 1.00088 1.2648 0.117499 1374 | 1.02813 1.29864 0.118759 1375 | 1.00416 1.33449 0.146235 1376 | -0.369484 0.905434 0.383463 1377 | -0.577603 0.890901 0.40792 1378 | -0.528114 0.831299 0.365099 1379 | -0.383202 0.823412 0.247622 1380 | -0.376299 0.859039 0.354876 1381 | -0.12579 0.931032 0.298522 1382 | -0.39137 0.806882 0.171098 1383 | -0.130013 0.884055 0.179313 1384 | 0.439154 0.382628 0.419174 1385 | 0.415747 0.379789 0.408462 1386 | 0.42291 0.295855 0.436939 1387 | 0.522568 0.407389 0.399245 1388 | 0.487445 0.398405 0.394533 1389 | 0.501035 0.32676 0.420946 1390 | 0.537304 0.407305 0.365593 1391 | 0.549334 0.332949 0.418936 1392 | 0.423135 0.270795 0.430922 1393 | 0.45456 0.302969 0.435907 1394 | 0.417259 0.229288 0.433725 1395 | 0.452806 0.241309 0.426117 1396 | 0.456954 0.221023 0.413444 1397 | 0.589985 0.275591 0.37754 1398 | 0.56526 0.330502 0.374264 1399 | 0.465272 0.397135 0.400312 1400 | 0.473035 0.312879 0.441598 1401 | 0.410297 0.277892 0.369155 1402 | 0.411717 0.22212 0.358272 1403 | 0.426122 0.230482 0.310999 1404 | 0.408023 0.371273 0.365461 1405 | 0.423729 0.393798 0.326943 1406 | 0.441185 0.289591 0.314032 1407 | 0.531371 0.261463 0.42717 1408 | 0.580266 0.266514 0.419584 1409 | 0.495207 0.250715 0.440439 1410 | 0.476059 0.244126 0.43682 1411 | 0.540508 0.347941 0.33825 1412 | 0.477085 0.302537 0.297462 1413 | 0.515951 0.335162 0.312066 1414 | 0.539076 0.263199 0.319004 1415 | 0.572397 0.271623 0.347124 1416 | 0.48892 0.402297 0.311572 1417 | 0.469952 0.406 0.314221 1418 | -1.59235 0.813428 0.408365 1419 | -1.54696 0.845956 0.332554 1420 | -1.484 0.937248 0.392455 1421 | -1.62812 0.763859 0.444996 1422 | -1.52623 0.924482 0.437674 1423 | -1.66895 0.772539 0.479754 1424 | -1.56058 0.915066 0.480107 1425 | -1.71592 0.780301 0.490563 1426 | -1.60356 0.921356 0.494578 1427 | -1.76667 0.794667 0.481658 1428 | -1.64432 0.943423 0.499723 1429 | -1.88389 0.826503 0.338237 1430 | -1.88036 0.827234 0.400228 1431 | -1.82547 0.948568 0.393607 1432 | -1.80511 1.00153 0.392695 1433 | -1.81222 1.00124 0.321539 1434 | -1.83484 0.948188 0.298736 1435 | -1.74252 0.598564 0.463916 1436 | -1.73576 0.476367 0.46869 1437 | -1.69883 0.477425 0.463585 1438 | -1.73885 0.673118 0.476796 1439 | -1.69431 0.606926 0.458401 1440 | -1.68528 0.673299 0.470933 1441 | -1.75558 0.676129 0.474402 1442 | -1.78836 0.587151 0.443771 1443 | -1.77502 0.472986 0.453358 1444 | -1.80851 0.688242 0.445292 1445 | -1.82194 0.804586 0.432196 1446 | -1.83578 0.5869 0.421057 1447 | -1.81723 0.468763 0.423199 1448 | -1.86337 0.687541 0.412954 1449 | -1.6742 0.491416 0.433751 1450 | -1.66743 0.602293 0.436012 1451 | -1.65077 0.678452 0.435377 1452 | -1.61672 0.743308 0.389216 1453 | -1.65584 0.658712 0.380501 1454 | -1.67763 0.584436 0.391953 1455 | -1.68468 0.496424 0.3992 1456 | -1.68194 0.652753 0.358399 1457 | -1.64836 0.731001 0.344451 1458 | -1.71737 0.652078 0.339982 1459 | -1.69324 0.742286 0.319303 1460 | -1.7758 0.661075 0.33746 1461 | -1.75715 0.78757 0.311016 1462 | -1.76811 0.573803 0.363856 1463 | -1.77017 0.476768 0.37958 1464 | -1.72762 0.574553 0.368 1465 | -1.7985 0.9058 0.285772 1466 | -1.72558 0.859387 0.283611 1467 | -1.8322 0.797361 0.30939 1468 | -1.85046 0.690416 0.343275 1469 | -1.81379 0.576973 0.366934 1470 | -1.79545 0.479611 0.38196 1471 | -1.86856 0.686409 0.374472 1472 | -1.84578 0.564648 0.38379 1473 | -1.82814 0.470733 0.400973 1474 | 0.533448 0.624065 0.395833 1475 | 0.509387 0.517291 0.396534 1476 | 0.519596 0.517865 0.368256 1477 | 0.545689 0.698743 0.403719 1478 | 0.550727 0.635517 0.359744 1479 | 0.549432 0.829496 0.404182 1480 | 0.56094 0.699523 0.361256 1481 | 0.555801 0.907171 0.428453 1482 | 0.563325 0.83699 0.365726 1483 | 0.424259 0.507823 0.406933 1484 | 0.39841 0.495427 0.395216 1485 | 0.41226 0.601623 0.422789 1486 | 0.385102 0.598189 0.411799 1487 | 0.416501 0.675089 0.430304 1488 | 0.374566 0.683142 0.426796 1489 | 0.415231 0.805586 0.444737 1490 | 0.351679 0.797625 0.436684 1491 | 0.385772 0.877725 0.466451 1492 | 0.337913 0.878726 0.44919 1493 | 0.35756 0.600953 0.390465 1494 | 0.332428 0.681035 0.393277 1495 | 0.323353 0.806005 0.414 1496 | 0.31097 0.88026 0.422415 1497 | 0.388252 0.491993 0.374286 1498 | 0.364158 0.603871 0.349351 1499 | 0.338943 0.686043 0.348791 1500 | 0.307998 0.801434 0.354587 1501 | 0.298274 0.90815 0.311908 1502 | 0.39158 0.507404 0.350703 1503 | 0.397796 0.616734 0.309068 1504 | 0.382725 0.687868 0.306093 1505 | 0.362156 0.844157 0.303929 1506 | 0.363541 0.89992 0.276833 1507 | 0.479995 0.514462 0.414546 1508 | 0.512148 0.886744 0.454765 1509 | 0.514246 0.827658 0.44181 1510 | 0.50405 0.684747 0.443494 1511 | 0.498641 0.597188 0.427457 1512 | 0.45225 0.507968 0.415864 1513 | 0.453925 0.905901 0.482254 1514 | 0.460062 0.828751 0.453333 1515 | 0.469045 0.673458 0.442206 1516 | 0.459806 0.583277 0.429114 1517 | 0.43251 0.524847 0.313084 1518 | 0.41702 0.902274 0.26746 1519 | 0.425448 0.862759 0.294865 1520 | 0.428684 0.691862 0.283731 1521 | 0.439849 0.620111 0.28642 1522 | 0.527857 0.40034 0.342649 1523 | 0.464385 0.511204 0.298996 1524 | 0.516669 0.526244 0.325057 1525 | 0.523674 0.902869 0.272278 1526 | 0.536343 0.832533 0.289871 1527 | 0.515761 0.714673 0.298665 1528 | 0.566296 0.914995 0.380762 1529 | 0.505477 0.652144 0.307464 1530 | 0.602192 1.059 0.417036 1531 | 0.589091 0.996277 0.397341 1532 | 0.583806 1.04782 0.467513 1533 | 0.57141 0.98165 0.445662 1534 | 0.525235 1.06186 0.510695 1535 | 0.52855 0.955603 0.473328 1536 | 0.454049 1.04411 0.515809 1537 | 0.452546 0.957251 0.499922 1538 | 0.364348 1.04678 0.505274 1539 | 0.369056 0.948321 0.486897 1540 | 0.318398 1.0376 0.481841 1541 | 0.32687 0.962726 0.473139 1542 | 0.289014 1.02966 0.45392 1543 | 0.299593 0.972786 0.432607 1544 | 0.252602 1.0381 0.374697 1545 | 0.244072 1.00699 0.33658 1546 | 0.618136 1.10611 0.431658 1547 | 0.605401 1.117 0.471767 1548 | 0.550802 1.12953 0.51896 1549 | 0.4689 1.12399 0.531718 1550 | 0.383788 1.12389 0.519533 1551 | 0.330269 1.1072 0.50564 1552 | 0.292373 1.09718 0.486165 1553 | 0.236138 1.10234 0.405395 1554 | 0.637814 1.18124 0.449167 1555 | 0.37908 1.17777 0.52447 1556 | 0.481578 1.19742 0.534151 1557 | 0.565565 1.19275 0.515015 1558 | 0.609822 1.18192 0.493032 1559 | 0.288163 1.1683 0.501964 1560 | 0.248045 1.18636 0.452324 1561 | 0.335396 1.16866 0.524749 1562 | 0.984735 2.47235 0.0172057 1563 | 1.08387 2.51096 0.0340487 1564 | 0.996751 2.44695 0.0769884 1565 | 1.09191 2.49648 0.0674534 1566 | 1.00646 2.38495 0.133192 1567 | 1.10254 2.42482 0.131838 1568 | 1.01893 2.32309 0.151494 1569 | 1.12952 2.37419 0.152089 1570 | 1.03159 2.26111 0.16973 1571 | 1.14702 2.30317 0.178789 1572 | 1.05266 2.13662 0.20597 1573 | 1.18941 2.20546 0.20254 1574 | 1.06434 2.00328 0.222579 1575 | 1.21367 2.07056 0.21787 1576 | 1.10446 1.82841 0.222275 1577 | 1.22732 1.91468 0.201604 1578 | 1.12259 1.72081 0.207429 1579 | 1.25388 1.81133 0.174803 1580 | 1.13944 1.6762 0.184039 1581 | 1.26338 1.78286 0.161782 1582 | 1.14771 1.63575 0.158768 1583 | 1.27815 1.75261 0.137819 1584 | 1.17422 1.56684 0.115414 1585 | 1.28946 1.72041 0.10825 1586 | 1.20774 1.54952 0.084812 1587 | 1.30561 1.6834 0.0800642 1588 | 1.18275 2.55172 0.047374 1589 | 1.30124 2.62082 0.0682637 1590 | 1.47481 1.8797 0.0838721 1591 | 1.37289 1.81275 0.111159 1592 | 1.40198 1.79386 0.0892194 1593 | 1.46791 1.89973 0.134362 1594 | 1.36064 1.85038 0.139635 1595 | 1.45162 1.95542 0.178801 1596 | 1.35514 1.89614 0.172802 1597 | 1.4399 2.06158 0.221168 1598 | 1.34358 1.97928 0.205563 1599 | 1.41647 2.17533 0.239955 1600 | 1.31034 2.12558 0.230751 1601 | 1.37131 2.28657 0.224655 1602 | 1.26769 2.24848 0.213101 1603 | 1.36952 2.38103 0.212096 1604 | 1.24104 2.35311 0.18373 1605 | 1.33994 2.47094 0.197399 1606 | 1.21929 2.41839 0.172436 1607 | 1.31496 2.57597 0.144524 1608 | 1.19206 2.47528 0.142068 1609 | 1.30943 2.60212 0.108765 1610 | 1.18359 2.53049 0.0816295 1611 | 1.13156 1.43368 0.0908779 1612 | 0.699085 2.38201 0.0914261 1613 | 0.855409 2.40915 0.07605 1614 | 0.71931 2.32853 0.15265 1615 | 0.865293 2.34704 0.132183 1616 | 0.768707 2.25826 0.188567 1617 | 0.881842 2.28153 0.157653 1618 | 0.784065 2.16937 0.227967 1619 | 0.899337 2.2105 0.184353 1620 | 0.820913 2.05167 0.258502 1621 | 0.916494 2.08547 0.220169 1622 | 0.869613 1.91721 0.273516 1623 | 0.957974 1.94856 0.229165 1624 | 0.897636 1.81003 0.291929 1625 | 1.00766 1.77835 0.25523 1626 | 0.936088 1.72311 0.289221 1627 | 0.945402 1.64066 0.285324 1628 | 1.04082 1.67873 0.240115 1629 | 0.960019 1.54696 0.231563 1630 | 1.05397 1.61264 0.203686 1631 | 1.0687 1.53548 0.169695 1632 | 1.10699 1.47067 0.12393 1633 | 0.839422 1.90627 0.319757 1634 | 0.871914 1.77994 0.316482 1635 | 0.888454 1.69987 0.318739 1636 | 0.888445 1.62278 0.318399 1637 | 0.867877 1.54601 0.318748 1638 | 0.714633 2.15084 0.265603 1639 | 0.75279 2.04302 0.311761 1640 | 0.766565 2.03908 0.299462 1641 | 0.779442 1.36167 0.415241 1642 | 0.844329 1.441 0.363296 1643 | 0.801977 1.41681 0.434672 1644 | 0.849618 1.51623 0.352835 1645 | 0.807676 1.51145 0.431569 1646 | 0.863553 1.62034 0.38378 1647 | 0.826186 1.61714 0.453865 1648 | 0.862375 1.69978 0.39514 1649 | 0.83479 1.69413 0.449267 1650 | 0.851549 1.77675 0.376626 1651 | 0.811454 1.80061 0.425631 1652 | 0.80626 1.92452 0.341401 1653 | 0.791352 1.92886 0.368171 1654 | 0.779027 2.04403 0.288027 1655 | 0.598271 2.37723 0.0815876 1656 | 0.620586 2.33238 0.152779 1657 | 0.672756 2.21938 0.242813 1658 | 0.69247 1.27469 0.448796 1659 | 0.648191 1.22222 0.441073 1660 | 0.570496 2.36489 0.0959052 1661 | 0.582478 2.34314 0.146184 1662 | 0.623601 2.25079 0.230243 1663 | 0.657173 2.16451 0.294525 1664 | 0.693016 2.0732 0.336592 1665 | 0.71597 1.948 0.405587 1666 | 0.737825 1.83681 0.459393 1667 | 0.758274 1.71368 0.501155 1668 | 0.760536 1.58781 0.51795 1669 | 0.739421 1.49566 0.504117 1670 | 0.733796 1.42895 0.50082 1671 | 0.709468 1.34232 0.461914 1672 | 0.545883 1.3113 0.527345 1673 | 0.455096 2.37755 0.0804243 1674 | 0.587927 1.44582 0.557408 1675 | 0.599984 1.52052 0.565506 1676 | 0.602417 1.57887 0.573224 1677 | 0.575929 1.72811 0.557307 1678 | 0.550247 1.83659 0.506587 1679 | 0.529309 1.96822 0.451053 1680 | 0.521514 2.10148 0.382018 1681 | 0.477957 2.24259 0.280812 1682 | 0.461427 2.31657 0.1801 1683 | 0.451186 2.35899 0.116447 1684 | -0.243122 2.3456 0.0729816 1685 | -0.0164301 2.3104 0.126306 1686 | -0.237091 2.30667 0.129375 1687 | -0.0216975 2.25479 0.205691 1688 | -0.214296 2.26289 0.191697 1689 | -0.00637012 2.13444 0.310935 1690 | -0.206966 2.1756 0.279713 1691 | 0.0362125 2.03745 0.387407 1692 | -0.23438 2.10316 0.363586 1693 | 0.0644202 1.93635 0.44264 1694 | -0.202261 1.94942 0.480961 1695 | 0.072333 1.77075 0.524869 1696 | -0.103996 1.75928 0.555118 1697 | 0.0672682 1.6893 0.545662 1698 | -0.104044 1.6686 0.58444 1699 | 0.07716 1.62209 0.555867 1700 | -0.113861 1.59412 0.600142 1701 | 0.0743565 1.55867 0.564057 1702 | -0.102616 1.52027 0.606203 1703 | 0.0816122 1.46746 0.55011 1704 | -0.100636 1.43092 0.603056 1705 | 0.0878759 1.3717 0.504804 1706 | -0.0989703 1.32421 0.588981 1707 | 0.0765427 1.32176 0.488322 1708 | -0.109078 1.22289 0.554818 1709 | 0.0726457 1.20884 0.451668 1710 | -0.101541 1.10375 0.48565 1711 | 0.0799102 1.13135 0.408138 1712 | -0.1078 1.02295 0.412008 1713 | 0.0685371 1.06699 0.368527 1714 | -0.104217 0.98232 0.339306 1715 | 0.0650325 1.03194 0.323172 1716 | 0.0606197 0.961836 0.256111 1717 | 0.0607472 0.94233 0.187067 1718 | -0.588431 2.35006 0.0841663 1719 | -0.439353 2.34661 0.0688652 1720 | -0.587514 2.32674 0.121789 1721 | -0.459418 2.32047 0.119638 1722 | -0.617872 2.30212 0.197468 1723 | -0.45103 2.29318 0.173664 1724 | -0.605216 2.25989 0.284709 1725 | -0.420852 2.25181 0.242152 1726 | -0.639101 2.19085 0.33761 1727 | -0.426582 2.17874 0.310729 1728 | -0.743111 2.13404 0.371413 1729 | -0.520743 2.0463 0.430194 1730 | -0.768884 2.0005 0.507394 1731 | -0.392484 1.80532 0.595546 1732 | -0.673378 1.79638 0.648951 1733 | -0.339265 1.67533 0.651114 1734 | -0.626245 1.68227 0.700512 1735 | -0.333732 1.60451 0.673569 1736 | -0.578316 1.53957 0.743672 1737 | -0.326679 1.50404 0.682275 1738 | -0.576888 1.34657 0.752127 1739 | -0.337082 1.38182 0.696976 1740 | -0.564333 1.20042 0.72753 1741 | -0.332427 1.23652 0.668433 1742 | -0.556475 1.07713 0.66512 1743 | -0.360032 1.09903 0.617136 1744 | -0.572794 0.986433 0.58092 1745 | -0.373419 1.00948 0.547576 1746 | -0.573627 0.944234 0.516879 1747 | -0.373578 0.963961 0.481464 1748 | -0.877541 2.37779 0.0609719 1749 | -0.735852 2.3582 0.0690911 1750 | -0.882852 2.35663 0.123805 1751 | -0.762634 2.34273 0.131299 1752 | -0.911567 2.33345 0.228718 1753 | -0.790348 2.31199 0.241034 1754 | -0.931725 2.3146 0.32191 1755 | -0.802827 2.26847 0.337611 1756 | -0.960535 2.27904 0.400105 1757 | -0.833473 2.21702 0.363425 1758 | -1.02563 2.22039 0.465064 1759 | -0.90546 2.12872 0.419505 1760 | -1.02624 2.10077 0.50952 1761 | -0.871015 2.03472 0.488514 1762 | -0.98288 1.98897 0.548232 1763 | -0.847723 1.9594 0.554989 1764 | -0.961346 1.8562 0.598183 1765 | -0.835729 1.79016 0.644385 1766 | -0.993922 1.73361 0.636914 1767 | -0.816592 1.67598 0.686879 1768 | -0.998383 1.59257 0.66819 1769 | -0.80607 1.45225 0.747208 1770 | -0.956858 1.29525 0.686822 1771 | -0.816552 1.2199 0.722034 1772 | -0.948338 1.18502 0.642013 1773 | -0.809527 1.09989 0.661682 1774 | -0.959878 1.10608 0.579171 1775 | -0.783118 1.01437 0.598695 1776 | -0.962215 1.05839 0.49272 1777 | -0.761588 0.968223 0.517281 1778 | 0.381266 1.30589 0.551726 1779 | 0.383065 1.22509 0.534838 1780 | 0.302981 2.37267 0.100156 1781 | 0.312384 2.35156 0.129421 1782 | 0.318247 2.31689 0.178938 1783 | 0.32169 2.25718 0.26043 1784 | 0.327059 2.19145 0.3288 1785 | 0.35067 2.01687 0.438134 1786 | 0.355748 1.94315 0.472989 1787 | 0.37685 1.78849 0.518916 1788 | 0.385203 1.70219 0.536373 1789 | 0.390197 1.61179 0.551373 1790 | 0.391872 1.51964 0.560511 1791 | 0.398251 1.42249 0.571289 1792 | 0.183756 1.0167 0.301307 1793 | 0.19192 0.959636 0.256401 1794 | 0.197588 0.927634 0.193665 1795 | 0.195715 1.06619 0.364925 1796 | 0.263623 1.35436 0.489771 1797 | 0.210611 1.19381 0.443658 1798 | 0.200543 1.12477 0.396447 1799 | -0.761901 0.92178 0.398496 1800 | -0.943831 2.38331 0.0611529 1801 | -0.957227 2.36311 0.120107 1802 | -0.966598 2.34212 0.235431 1803 | -0.987686 2.33293 0.320452 1804 | -1.03915 2.29423 0.43516 1805 | -1.10069 2.21653 0.492888 1806 | -1.10594 2.08102 0.522942 1807 | -1.13843 1.89292 0.535254 1808 | -1.13347 1.80266 0.550339 1809 | -1.13998 1.73002 0.571771 1810 | -1.13302 1.61799 0.606551 1811 | -1.13642 1.4787 0.619846 1812 | -1.15185 1.36483 0.573354 1813 | -1.12763 1.26347 0.519473 1814 | -1.11646 1.18653 0.476366 1815 | -1.08397 2.39188 0.0556873 1816 | -1.09744 2.37376 0.111269 1817 | -1.1108 2.36799 0.193357 1818 | -1.19235 2.31612 0.357594 1819 | -1.22161 2.21504 0.471196 1820 | -1.21468 2.10314 0.506064 1821 | -1.22935 1.96062 0.512954 1822 | -1.23663 1.84464 0.526588 1823 | -1.23265 1.78485 0.546389 1824 | -1.19375 1.70594 0.577206 1825 | -1.1781 1.61993 0.604188 1826 | -1.20152 1.48177 0.609139 1827 | -1.23816 1.37138 0.565327 1828 | -1.2455 1.27018 0.493267 1829 | -1.24254 1.21717 0.45567 1830 | -1.23805 1.2021 0.427168 1831 | -1.12736 1.15336 0.417981 1832 | -0.870025 0.961382 0.392435 1833 | -0.983815 1.03216 0.39632 1834 | -0.944239 1.01247 0.402195 1835 | -1.25841 2.40454 0.0631288 1836 | -1.26748 2.39229 0.103186 1837 | -1.28395 2.37607 0.193063 1838 | -1.29921 2.31869 0.357124 1839 | -1.31404 2.20099 0.478937 1840 | -1.35383 2.07174 0.518381 1841 | -1.3548 1.94193 0.532813 1842 | -1.3363 1.84451 0.547986 1843 | -1.29315 1.77143 0.563264 1844 | -1.25436 1.69483 0.590661 1845 | -1.25188 1.61153 0.624498 1846 | -1.30603 1.43774 0.622307 1847 | -1.34514 1.29917 0.561091 1848 | -1.35207 1.19157 0.499426 1849 | -1.35528 1.15122 0.462641 1850 | -1.3585 1.11087 0.425855 1851 | -1.51995 2.44304 0.0317397 1852 | -1.53073 2.42813 0.0985798 1853 | -1.53326 2.40792 0.176308 1854 | -1.53861 2.37324 0.268667 1855 | -1.5396 2.29832 0.388268 1856 | -1.52525 2.15956 0.491646 1857 | -1.47559 1.97154 0.554109 1858 | -1.45965 1.8927 0.56181 1859 | -1.45296 1.84967 0.563555 1860 | -1.43216 1.7359 0.582546 1861 | -1.41436 1.63773 0.606601 1862 | -1.40614 1.55547 0.617229 1863 | -1.39212 1.41923 0.608267 1864 | -1.41309 1.24076 0.555123 1865 | -1.47315 1.06929 0.5166 1866 | -1.68754 2.47112 0.0246564 1867 | -1.69837 2.42805 0.0979502 1868 | -1.69733 2.41698 0.162211 1869 | -1.7122 2.39207 0.25133 1870 | -1.70189 2.33382 0.347938 1871 | -1.67689 2.2475 0.417075 1872 | -1.63342 2.08972 0.498431 1873 | -1.58736 1.93646 0.535089 1874 | -1.57184 1.8099 0.541802 1875 | -1.57025 1.71984 0.547568 1876 | -1.52617 1.63709 0.571024 1877 | -1.50956 1.49669 0.592658 1878 | -1.49507 1.37783 0.594637 1879 | -1.49877 1.21172 0.558072 1880 | -1.54325 1.06772 0.526863 1881 | -1.89323 2.34611 0.141926 1882 | -1.82217 2.40123 0.169684 1883 | -1.89651 2.30128 0.228127 1884 | -1.83842 2.36423 0.246681 1885 | -1.89027 2.24156 0.271639 1886 | -1.81346 2.30807 0.306133 1887 | -1.87406 2.17092 0.312802 1888 | -1.78672 2.23467 0.378566 1889 | -1.85904 2.09055 0.33844 1890 | -1.77203 2.13025 0.403688 1891 | -1.83126 1.94175 0.39269 1892 | -1.75072 1.95482 0.436731 1893 | -1.79941 1.77063 0.437486 1894 | -1.71375 1.80486 0.480331 1895 | -1.77486 1.68042 0.466499 1896 | -1.68381 1.70213 0.515645 1897 | -1.73476 1.59494 0.493031 1898 | -1.65159 1.61737 0.538144 1899 | -1.70871 1.44686 0.514534 1900 | -1.62318 1.45091 0.567057 1901 | -1.70657 1.30874 0.504691 1902 | -1.62057 1.33016 0.568158 1903 | -1.71794 1.16301 0.471599 1904 | -1.63665 1.16122 0.53966 1905 | -1.73035 1.04801 0.443391 1906 | -1.6565 1.04578 0.501834 1907 | -1.74743 0.982462 0.426901 1908 | -1.69197 0.968232 0.483025 1909 | -1.98813 2.30388 0.132259 1910 | -1.97181 2.24978 0.193193 1911 | -1.96593 2.19865 0.223168 1912 | -1.95293 2.12823 0.255021 1913 | -1.9462 2.05075 0.273319 1914 | -1.92107 1.92699 0.309725 1915 | -1.88654 1.78203 0.37553 1916 | -1.85115 1.67318 0.40692 1917 | -1.82521 1.55324 0.42196 1918 | -1.79214 1.41623 0.435955 1919 | -1.76699 1.30183 0.449779 1920 | -1.76909 1.17153 0.426028 1921 | -1.78647 1.08426 0.405605 1922 | -1.977 2.19887 0.0954694 1923 | -1.97342 2.16424 0.121358 1924 | -1.97088 2.11326 0.141794 1925 | -1.96055 2.06355 0.163023 1926 | -1.95699 2.01446 0.165563 1927 | -1.94242 1.91226 0.187396 1928 | -1.91557 1.77321 0.233328 1929 | -1.89344 1.66503 0.2748 1930 | -1.86614 1.54773 0.324678 1931 | -1.84338 1.45185 0.33118 1932 | -1.78919 1.28103 0.352091 1933 | -1.42735 1.02777 0.428129 1934 | -1.81493 0.927047 0.408396 1935 | -1.58108 0.810576 0.316314 1936 | -1.72266 0.488582 0.376221 1937 | -1.77955 0.359688 0.48183 1938 | -1.80534 0.356845 0.471115 1939 | -1.79745 0.272915 0.499591 1940 | -1.68761 0.384444 0.461901 1941 | -1.72632 0.375461 0.457189 1942 | -1.71135 0.303816 0.483598 1943 | -1.67137 0.384365 0.428249 1944 | -1.65811 0.310009 0.481592 1945 | -1.7972 0.24785 0.493579 1946 | -1.76256 0.280029 0.498563 1947 | -1.80368 0.206348 0.496382 1948 | -1.7645 0.218369 0.488773 1949 | -1.75992 0.198078 0.476095 1950 | -1.61332 0.252646 0.440196 1951 | -1.64056 0.307558 0.43692 1952 | -1.75076 0.374191 0.462968 1953 | -1.7422 0.289934 0.50425 1954 | -1.81135 0.254952 0.431812 1955 | -1.80978 0.19918 0.420929 1956 | -1.79391 0.207538 0.373655 1957 | -1.81385 0.348329 0.428118 1958 | -1.79654 0.370858 0.389596 1959 | -1.77731 0.266651 0.376684 1960 | -1.67791 0.238523 0.489822 1961 | -1.62403 0.243574 0.48224 1962 | -1.71777 0.227776 0.503095 1963 | -1.73887 0.221181 0.499476 1964 | -1.66784 0.325001 0.400906 1965 | -1.73774 0.279593 0.360118 1966 | -1.69491 0.312218 0.374722 1967 | -1.66942 0.240259 0.381656 1968 | -1.6327 0.248683 0.40978 1969 | -1.7247 0.379357 0.374228 1970 | -1.7456 0.383056 0.376877 1971 | -1.68178 0.377396 0.405301 1972 | -1.78747 1.09099 0.347991 1973 | -1.77487 1.18526 0.363539 1974 | -1.84736 1.46705 0.297938 1975 | -1.919 1.97252 0.129306 1976 | -1.90947 1.91396 0.125837 1977 | -1.9007 1.79821 0.144073 1978 | -1.89197 1.66893 0.191839 1979 | -1.87166 1.56877 0.242991 1980 | -1.93914 2.00507 0.00213196 1981 | -2.03707 1.52001 0.0105783 1982 | -2.02447 1.66952 0.0235689 1983 | -2.02941 1.66896 0.00213229 1984 | -2.03639 1.82284 0.0255526 1985 | -2.05529 2.04576 0.0275408 1986 | -2.0436 2.25552 0.0295243 1987 | -1.97223 2.39139 0.0315077 1988 | -1.87119 2.4679 0.033491 1989 | -1.76915 2.48725 0.0354742 1990 | -2.01929 1.51944 0.0248207 1991 | -2.01098 1.67104 0.0392617 1992 | -2.02172 1.8245 0.0427001 1993 | -2.03936 2.0474 0.0461385 1994 | -2.02635 2.25476 0.0495768 1995 | -1.95548 2.3835 0.0530148 1996 | -1.86069 2.45115 0.0564528 1997 | -1.76442 2.468 0.0598908 1998 | -1.99502 1.51867 0.0300355 1999 | -1.99254 1.67311 0.0450098 2000 | -2.00168 1.82677 0.0489816 2001 | -2.0176 2.04964 0.0529533 2002 | -2.00279 2.25372 0.056925 2003 | -1.9326 2.37272 0.060892 2004 | -1.84636 2.42827 0.0648634 2005 | -1.97075 1.5179 0.0248339 2006 | -1.97411 1.67518 0.0392748 2007 | -1.98164 1.82903 0.0427132 2008 | -1.99583 2.05188 0.046156 2009 | -1.97922 2.25267 0.0495942 2010 | -1.90971 2.36194 0.0530322 2011 | -1.83201 2.40539 0.0564704 2012 | -1.95297 1.51733 0.0106 2013 | -1.96061 1.67669 0.0235907 2014 | -1.96696 1.83069 0.0255788 2015 | -1.97989 2.05352 0.0275625 2016 | -1.96196 2.2519 0.0295504 2017 | -1.89295 2.35404 0.0315383 2018 | -1.82151 2.38863 0.0335261 2019 | -1.94645 1.51712 -0.00884862 2020 | -1.95566 1.67725 0.00215847 2021 | -1.95294 1.51733 -0.0283016 2022 | -1.9606 1.6767 -0.0192826 2023 | -1.97071 1.51789 -0.0425529 2024 | -1.97408 1.67518 -0.0349842 2025 | -1.99498 1.51867 -0.0477808 2026 | -1.99251 1.67311 -0.0407456 2027 | -2.01925 1.51944 -0.0425881 2028 | -2.01095 1.67104 -0.0350237 2029 | -2.03703 1.52001 -0.028363 2030 | -2.02445 1.66952 -0.0193484 2031 | -2.04357 1.52022 -0.00887026 2032 | 1.75696 2.43257 0.272388 2033 | 1.83409 2.50764 0.254636 2034 | 1.79309 2.49427 0.283369 2035 | 1.85871 2.4892 0.232755 2036 | 1.80135 2.42054 0.274579 2037 | 1.83798 2.41463 0.255747 2038 | 1.8587 2.41623 0.231675 2039 | 1.8218 2.39496 0.261262 2040 | 1.84628 2.38928 0.246115 2041 | 1.85487 2.3995 0.225071 2042 | 1.86739 2.43002 0.206306 2043 | 1.8469 2.50848 0.222479 2044 | 1.82641 2.52221 0.236942 2045 | 1.8712 2.47524 0.214139 2046 | 1.81015 2.52656 0.240134 2047 | 1.78565 2.52418 0.25606 2048 | 1.77344 2.53697 0.262677 2049 | 1.75282 2.50235 0.281649 2050 | 1.80616 2.55507 0.24143 2051 | 1.83056 2.55388 0.229832 2052 | 1.86342 2.53148 0.208519 2053 | 1.8877 2.48608 0.201351 2054 | 1.89585 2.44123 0.197745 2055 | 1.8757 2.40879 0.196427 2056 | 1.85878 2.37944 0.227103 2057 | 1.83417 2.36923 0.247773 2058 | 1.80556 2.3708 0.263223 2059 | 1.79737 2.40381 0.267975 2060 | 1.78132 2.39576 0.268381 2061 | 1.90018 2.43572 0.182114 2062 | 1.90439 2.46778 0.179112 2063 | 1.888 2.3915 0.186108 2064 | 1.8711 2.37022 0.216158 2065 | 1.8262 2.34446 0.242007 2066 | 1.8018 2.34563 0.253451 2067 | 1.75318 2.36294 0.262769 2068 | 1.89198 2.49708 0.188268 2069 | 1.87586 2.52992 0.192694 2070 | 1.835 2.56472 0.216766 2071 | 1.81027 2.57062 0.235876 2072 | 1.74288 2.5008 0.272912 2073 | 1.77763 2.54819 0.253552 2074 | 1.74878 2.43295 0.276148 2075 | 1.72905 2.38263 0.256316 2076 | 1.74952 2.56392 0.247235 2077 | 1.79064 2.58876 0.213412 2078 | 1.81556 2.58208 0.186249 2079 | 1.86058 2.55045 0.15399 2080 | 1.88917 2.50838 0.13847 2081 | 1.90514 2.46468 0.147052 2082 | 1.9089 2.42495 0.155128 2083 | 1.7288 2.42429 0.26839 2084 | 1.78869 2.60068 0.127216 2085 | 1.74749 2.61675 0.165213 2086 | 1.84974 2.54953 0.101203 2087 | 1.89416 2.5041 0.0943487 2088 | 1.9184 2.45964 0.0952214 2089 | 1.92966 2.41022 0.128648 2090 | 1.92105 2.35948 0.149463 2091 | 1.90794 2.3193 0.193553 2092 | 1.85478 2.26582 0.225878 2093 | 1.77349 2.25263 0.253653 2094 | 1.8303 2.25871 0.23413 2095 | 1.73701 2.26543 0.259701 2096 | 1.69282 2.32602 0.256806 2097 | 1.72487 2.50531 0.268598 2098 | 1.66464 2.41511 0.255669 2099 | 1.65654 2.48002 0.25734 2100 | 1.70216 2.60097 0.210182 2101 | 1.66897 2.54352 0.243353 2102 | 1.9314 2.4597 0.0550105 2103 | 1.95881 2.39827 0.0899756 2104 | 1.95794 2.3247 0.125457 2105 | 1.96514 2.2391 0.162128 2106 | 1.7209 2.23732 0.262047 2107 | 1.66841 2.31032 0.261902 2108 | 1.68447 2.27019 0.266156 2109 | 1.66872 2.39016 0.250044 2110 | 1.63215 2.34727 0.265464 2111 | 1.61224 2.43147 0.256859 2112 | 1.61242 2.49576 0.250644 2113 | 1.70145 2.64758 0.0638849 2114 | 1.67614 2.65658 0.115055 2115 | 1.62976 2.62819 0.197733 2116 | 1.59323 2.56881 0.210764 2117 | 1.96073 2.20781 0.173183 2118 | 1.93214 2.14843 0.186395 2119 | 1.84267 2.14841 0.224829 2120 | 1.75726 2.20408 0.253984 2121 | 2.00391 2.39475 0.0548428 2122 | 2.04829 2.34617 0.0565794 2123 | 2.02683 2.2826 0.110869 2124 | 2.03127 2.31721 0.0913595 2125 | 2.00973 2.22158 0.148748 2126 | 1.99326 2.18619 0.159919 2127 | 1.97725 2.12524 0.15731 2128 | 1.97277 2.09829 0.171931 2129 | 1.8587 2.11595 0.224353 2130 | 1.74494 2.14428 0.263466 2131 | 1.70434 2.16987 0.276317 2132 | 1.65175 2.21962 0.286393 2133 | 1.61153 2.28022 0.283749 2134 | 1.62417 2.3874 0.261399 2135 | 1.59186 2.38387 0.265138 2136 | 1.58777 2.42832 0.264728 2137 | 2.12899 2.28478 0.052268 2138 | 2.112 2.26388 0.0862722 2139 | 2.09518 2.23809 0.112615 2140 | 2.07038 2.19622 0.140487 2141 | 2.05004 2.16059 0.147448 2142 | 2.03778 2.12086 0.15499 2143 | 2.03359 2.0967 0.157229 2144 | 2.18433 2.23611 0.0946209 2145 | 2.18934 2.24857 0.0571696 2146 | 2.1652 2.2643 0.0509454 2147 | 2.14764 2.218 0.115771 2148 | 2.13079 2.18418 0.143053 2149 | 2.1754 2.20304 0.129983 2150 | 2.16286 2.16859 0.14929 2151 | 2.15866 2.11668 0.158199 2152 | 2.11064 2.14778 0.14196 2153 | 2.16211 2.26887 0.0025369 2154 | 2.16439 2.24339 0.0853198 2155 | 2.11837 2.12082 0.156864 2156 | 2.07378 2.09312 0.162656 2157 | 2.25328 2.21407 0.0780947 2158 | 2.26571 2.21252 0.0624281 2159 | 2.23356 2.2326 0.0597393 2160 | 2.29406 2.18756 0.0573675 2161 | 2.27733 2.18989 0.0809951 2162 | 2.22083 2.22725 0.0881893 2163 | 2.30232 2.14627 0.0494285 2164 | 2.27433 2.06821 0.0360765 2165 | 2.26958 2.0552 0.0695957 2166 | 2.28627 2.09298 0.0419303 2167 | 2.24046 2.04274 0.106488 2168 | 2.25241 2.07148 0.112117 2169 | 2.21534 2.0787 0.142934 2170 | 2.28142 2.08052 0.0795448 2171 | 2.28529 2.11337 0.084592 2172 | 2.16258 2.06828 0.158984 2173 | 2.19911 2.07144 0.151393 2174 | 2.16657 2.08502 0.165592 2175 | 2.12608 2.08582 0.172706 2176 | 2.06987 2.04828 0.158768 2177 | 2.15875 2.04745 0.152777 2178 | 2.11812 2.06498 0.166407 2179 | 2.09827 2.03532 0.152548 2180 | 2.11834 2.04376 0.156343 2181 | 2.05393 2.03101 0.147946 2182 | 2.04985 2.05991 0.153192 2183 | 2.07423 2.01822 0.141523 2184 | 2.02962 2.06425 0.156291 2185 | 2.02706 1.99353 0.0941762 2186 | 2.02576 2.03536 0.15086 2187 | 2.08785 1.9839 0.0804095 2188 | 2.10319 2.00705 0.1109 2189 | 2.12832 1.97915 0.0736781 2190 | 2.14375 2.00192 0.100219 2191 | 2.17296 1.97757 0.0585979 2192 | 2.19235 2.00901 0.092527 2193 | 1.96879 2.0619 0.171376 2194 | 1.99416 2.00394 0.116808 2195 | 1.9609 2.03261 0.161744 2196 | 2.21386 1.99117 0.0339916 2197 | 2.23087 2.02013 0.00253664 2198 | 2.23766 2.01276 0.0485603 2199 | 2.11305 1.97117 0.0335865 2200 | 2.06035 1.97685 0.0479219 2201 | 1.97157 1.9773 0.0499675 2202 | 2.01967 1.97843 0.0630903 2203 | 1.97891 1.98039 0.0822084 2204 | 1.94944 2.00985 0.13545 2205 | 1.92278 1.9667 0.0659648 2206 | 1.84627 1.95474 0.0653479 2207 | 1.93012 1.96981 0.0983688 2208 | 1.8609 1.96055 0.125884 2209 | 1.73543 1.9429 0.14908 2210 | 1.86439 2.00378 0.154317 2211 | 1.74281 1.9906 0.180999 2212 | 1.86724 2.07349 0.204256 2213 | 1.87172 2.02259 0.180898 2214 | 1.74917 2.07016 0.25048 2215 | 1.74989 2.02243 0.218591 2216 | 1.67188 2.11009 0.285331 2217 | 1.64027 2.05488 0.257564 2218 | 1.5977 1.97814 0.174855 2219 | 1.60513 2.00935 0.204381 2220 | 1.56855 2.02253 0.214378 2221 | 1.71675 1.92864 0.0851231 2222 | 1.57981 1.912 0.0755801 2223 | 1.56251 1.92548 0.130487 2224 | 1.51692 1.97896 0.181031 2225 | 1.61947 2.15908 0.287513 2226 | 1.55285 2.00505 0.199598 2227 | 1.48378 2.04792 0.222233 2228 | 1.54374 2.07833 0.244926 2229 | 1.49888 2.19849 0.272772 2230 | 1.45926 2.1714 0.242102 2231 | 1.58326 2.10186 0.280085 2232 | 1.53075 2.21203 0.28847 2233 | 1.56683 2.24895 0.293711 2234 | 1.59972 2.33606 0.273927 2235 | 1.55917 2.3453 0.284211 2236 | 1.55538 2.39667 0.271185 2237 | 1.5558 2.44367 0.254369 2238 | 1.52739 2.3835 0.25953 2239 | 1.51932 2.33533 0.264 2240 | 1.47493 2.31491 0.260959 2241 | 1.45133 2.2965 0.237954 2242 | 1.48717 2.37904 0.255043 2243 | 1.45542 2.37317 0.234621 2244 | 1.57245 2.74106 0.0639736 2245 | 1.62096 2.7161 0.0595344 2246 | 1.56793 2.7434 0.0880419 2247 | 1.61556 2.70992 0.120768 2248 | 1.57124 2.74611 0.11624 2249 | 1.50408 2.74504 0.061999 2250 | 1.51117 2.74459 0.0987273 2251 | 1.51484 2.75047 0.118497 2252 | 1.51408 2.74962 0.150937 2253 | 1.61104 2.7034 0.137399 2254 | 1.56639 2.73348 0.153709 2255 | 1.60265 2.70534 0.157271 2256 | 1.63062 2.66932 0.161406 2257 | 1.45615 2.6664 0.210266 2258 | 1.46049 2.71008 0.202154 2259 | 1.4494 2.70954 0.153314 2260 | 1.44085 2.65525 0.178616 2261 | 1.4459 2.7076 0.133164 2262 | 1.45879 2.73656 0.0982911 2263 | 1.4664 2.73044 0.119313 2264 | 1.46602 2.732 0.13542 2265 | 1.47328 2.73547 0.171611 2266 | 1.43433 2.71372 0.112049 2267 | 1.42159 2.67184 0.140204 2268 | 1.4373 2.66099 0.153741 2269 | 1.43222 2.71759 0.0016831 2270 | 1.36448 2.61363 0.164762 2271 | 1.40475 2.63816 0.167314 2272 | 1.43272 2.64325 0.17959 2273 | 1.45573 2.6194 0.227083 2274 | 1.40703 2.60858 0.239117 2275 | 1.35891 2.54727 0.231813 2276 | 1.37918 2.59132 0.228022 2277 | 1.47176 2.63216 0.234193 2278 | 1.42632 2.60399 0.27637 2279 | 1.47105 2.61087 0.264622 2280 | 1.39018 2.58358 0.273518 2281 | 1.3741 2.55074 0.268189 2282 | 1.44126 2.59704 0.330176 2283 | 1.48593 2.60746 0.313935 2284 | 1.3975 2.54222 0.306077 2285 | 1.41746 2.57543 0.315448 2286 | 1.51542 2.61851 0.260923 2287 | 1.55236 2.59966 0.23522 2288 | 1.51502 2.60805 0.278036 2289 | 1.49743 2.61861 0.345497 2290 | 1.52264 2.60588 0.298674 2291 | 1.45642 2.60129 0.37461 2292 | 1.43243 2.56768 0.361037 2293 | 1.5165 2.63936 0.392572 2294 | 1.54188 2.62175 0.338092 2295 | 1.46777 2.61638 0.405783 2296 | 1.44786 2.57078 0.393626 2297 | 1.49011 2.65619 0.483467 2298 | 1.46664 2.61709 0.454329 2299 | 1.44886 2.58713 0.521563 2300 | 1.50716 2.66487 0.446663 2301 | 1.55691 2.64686 0.388798 2302 | 1.53891 2.67074 0.467086 2303 | 1.52228 2.67663 0.486381 2304 | 1.49668 2.68695 0.54954 2305 | 1.46303 2.67273 0.610892 2306 | 1.46446 2.64647 0.54872 2307 | 1.44212 2.63534 0.642411 2308 | 1.44724 2.61419 0.591947 2309 | 1.44244 2.57621 0.449591 2310 | 1.41688 2.53725 0.33938 2311 | 1.4315 2.53911 0.400296 2312 | 1.43049 2.54732 0.443971 2313 | 1.43783 2.48142 0.474916 2314 | 1.4325 2.53185 0.534664 2315 | 1.45812 2.56236 0.641705 2316 | 1.46708 2.50187 0.60327 2317 | 1.48862 2.42702 0.542112 2318 | 1.43543 2.47087 0.406987 2319 | 1.34367 2.54734 0.190946 2320 | 1.38735 2.47273 0.215278 2321 | 1.40683 2.47133 0.244253 2322 | 1.46303 2.43606 0.257102 2323 | 1.41401 2.47931 0.284155 2324 | 1.42926 2.48318 0.324639 2325 | 1.48779 2.40577 0.406364 2326 | 1.47792 2.40921 0.482828 2327 | 1.57261 2.53436 0.229882 2328 | 1.5603 2.54753 0.240443 2329 | 1.55617 2.51098 0.239897 2330 | 1.48719 2.65622 0.609063 2331 | 1.4833 2.61533 0.604795 2332 | 1.49622 2.61988 0.568133 2333 | 1.48741 2.63499 0.59884 2334 | 1.48403 2.60828 0.573119 2335 | 1.50867 2.65883 0.552537 2336 | 1.50861 2.63877 0.554473 2337 | 1.5094 2.61916 0.519869 2338 | 1.54271 2.58186 0.301465 2339 | 1.53938 2.53864 0.273191 2340 | 1.58948 2.57643 0.371968 2341 | 1.55519 2.63788 0.462506 2342 | 1.52992 2.65021 0.505221 2343 | 1.51784 2.64216 0.505719 2344 | 1.55226 2.59233 0.410072 2345 | 1.58453 2.61632 0.408498 2346 | 1.54896 2.56112 0.380639 2347 | 1.54294 2.62588 0.463383 2348 | 1.57777 2.53026 0.355905 2349 | 1.51491 2.60939 0.460183 2350 | 1.51975 2.58545 0.422101 2351 | 1.54954 2.53439 0.354851 2352 | 1.50865 2.55719 0.380083 2353 | 1.48906 2.52226 0.354622 2354 | 1.48814 2.53025 0.394335 2355 | 1.48716 2.55047 0.43701 2356 | 1.48967 2.56883 0.500037 2357 | 1.48879 2.58867 0.538608 2358 | 1.4797 2.50724 0.408485 2359 | 1.47444 2.51268 0.464609 2360 | 1.47715 2.53818 0.518978 2361 | 1.48025 2.56211 0.557241 2362 | 1.48222 2.46055 0.469828 2363 | 1.48493 2.49092 0.531705 2364 | 1.47589 2.52315 0.573031 2365 | 1.47121 2.57087 0.604668 2366 | 1.47088 2.58838 0.619232 2367 | 1.47881 2.62098 0.62025 2368 | 1.52396 2.44215 0.237671 2369 | 1.54411 2.47458 0.238989 2370 | 1.54554 2.50944 0.349037 2371 | 1.578 2.51315 0.345444 2372 | 1.52964 2.48863 0.342707 2373 | 1.49173 2.46278 0.409075 2374 | 1.76911 2.49723 0.270404 2375 | 1.46638 2.62254 0.636076 2376 | 1.44794 2.42336 0.209341 2377 | 1.34572 2.64027 0.104979 2378 | -1.66781 0.827741 0.291157 2379 | -1.79851 0.9058 -0.281508 2380 | -1.78748 1.09099 -0.343729 2381 | 1.51407 2.74962 -0.146699 2382 | 2.19529 2.04589 0.137671 2383 | -1.90016 1.68762 -0.147074 2384 | -1.90761 1.70005 0.00213184 2385 | -1.90416 1.80917 0.00213183 2386 | -1.91407 1.89284 0.00213187 2387 | -1.90015 1.68762 0.151338 2388 | -1.97178 1.18361 0.0456798 2389 | -1.96232 1.36022 0.0363257 2390 | -1.97261 1.26827 0.0412144 2391 | 0.588417 0.215459 -0.469025 2392 | 0.614866 0.221521 -0.429374 2393 | 0.63573 0.212003 -0.389727 2394 | -1.61505 0.19252 -0.53166 2395 | -1.5859 0.198581 -0.492009 2396 | -1.56291 0.189064 -0.452363 2397 | 0.588421 0.215459 0.47327 2398 | 0.526712 0.218281 0.471666 2399 | 0.61487 0.221521 0.433619 2400 | 0.635732 0.212003 0.393973 2401 | 0.622565 0.209606 0.354895 2402 | -1.61504 0.19252 0.535922 2403 | -1.68305 0.195336 0.534322 2404 | -1.58589 0.198581 0.496271 2405 | -1.5629 0.189064 0.456624 2406 | -1.57741 0.186666 0.417551 2407 | 2.24671 2.0535 0.00253658 2408 | 2.25808 2.04816 -0.0334041 2409 | 2.24965 2.0381 -0.0544351 2410 | 2.19626 2.0255 -0.0907754 2411 | 2.15989 2.02235 -0.0983701 2412 | 2.11528 2.02315 -0.105392 2413 | 2.25809 2.04816 0.0376369 2414 | 2.24966 2.0381 0.0586681 2415 | 2.19627 2.0255 0.0950088 2416 | 2.1599 2.02235 0.102604 2417 | 2.11529 2.02315 0.109626 2418 | 1.57318 2.74302 -0.205481 2419 | 1.60126 2.71922 -0.212419 2420 | 1.61718 2.6832 -0.216272 2421 | 1.61677 2.63618 -0.23293 2422 | 1.50703 2.64818 -0.269734 2423 | 1.55996 2.6301 -0.252454 2424 | 1.46751 2.72201 -0.237435 2425 | 1.47531 2.68677 -0.249157 2426 | 1.48817 2.74012 -0.215911 2427 | 1.5206 2.76016 0.218963 2428 | 1.57319 2.74302 0.209719 2429 | 1.60127 2.71922 0.216657 2430 | 1.61719 2.6832 0.22051 2431 | 1.61678 2.63618 0.237168 2432 | 1.55997 2.6301 0.256692 2433 | 1.50704 2.64818 0.273971 2434 | 1.47532 2.68677 0.253394 2435 | 1.46752 2.72201 0.241673 2436 | 1.48818 2.74012 0.220148 2437 | 1.52059 2.76016 -0.214725 2438 | -1.99061 1.3572 0.0398126 2439 | -1.98569 1.22002 0.0448687 2440 | -1.98759 1.09988 0.0511238 2441 | -1.95795 1.10056 0.0366299 2442 | -1.99199 1.00056 0.046632 2443 | -1.94612 1.05561 0.027342 2444 | -2.0272 0.916666 0.0380716 2445 | -1.92068 0.979962 -0.0438755 2446 | -1.96525 0.901485 -0.0486626 2447 | -2.05663 0.831783 0.00989508 2448 | -2.02935 0.815712 -0.0481642 2449 | -2.00748 1.36434 0.0304587 2450 | -2.01936 1.25106 0.0458784 2451 | -2.03585 1.17063 0.0533898 2452 | -2.05407 1.04718 0.0675135 2453 | -2.06704 0.947823 0.0678793 2454 | -2.11169 0.871523 0.0595835 2455 | -2.1522 0.793689 0.0550961 2456 | -2.02498 1.37284 0.0266282 2457 | -2.06129 1.25902 0.0425019 2458 | -2.08282 1.17839 0.0642031 2459 | -2.09371 1.08767 0.0745313 2460 | -2.11326 0.980297 0.0700836 2461 | -2.17298 0.863641 0.0752413 2462 | -2.19644 0.755642 0.0705027 2463 | -2.05919 1.3259 0.0364628 2464 | -2.0953 1.24027 0.0458962 2465 | -2.11805 1.14338 0.0622195 2466 | -2.16194 1.06158 0.0553607 2467 | -2.18612 0.898796 0.0687791 2468 | -2.23621 0.770158 0.0804695 2469 | -2.07519 1.35791 0.0185968 2470 | -2.13613 1.18551 0.0508644 2471 | -2.20529 1.06198 0.0329412 2472 | -2.20596 0.953888 0.0513098 2473 | -2.24148 0.834539 0.0684002 2474 | -2.28363 0.756251 0.0872009 2475 | -2.09407 1.35861 -0.00421956 2476 | -2.15453 1.2172 0.0093312 2477 | -2.20802 1.08902 0.0118616 2478 | -2.2521 0.920757 0.0272329 2479 | -2.29191 0.795796 0.059809 2480 | -2.30147 0.714955 0.0857551 2481 | -2.07052 1.36587 -0.0619218 2482 | -2.12379 1.21678 -0.0723512 2483 | -2.2003 1.09153 -0.0437246 2484 | -2.21634 0.969422 -0.0620579 2485 | -2.251 0.857135 -0.0170818 2486 | -2.2756 0.73581 0.0222342 2487 | -2.06552 1.338 -0.0697903 2488 | -2.09973 1.17884 -0.0964549 2489 | -2.15429 1.01558 -0.115634 2490 | -2.19396 0.867727 -0.0925797 2491 | -2.22533 0.810276 -0.0418952 2492 | -2.25991 0.744688 0.0131622 2493 | -2.04925 1.26865 -0.0847823 2494 | -2.06876 1.12592 -0.125336 2495 | -2.10561 0.996823 -0.12378 2496 | -2.13717 0.876134 -0.102948 2497 | -2.18243 0.806164 -0.0598717 2498 | -2.24657 0.737719 0.0131842 2499 | -1.99149 1.28173 -0.0637074 2500 | -2.00697 1.13977 -0.103883 2501 | -2.02578 1.05702 -0.116803 2502 | -2.10497 0.912271 -0.119244 2503 | -2.09511 0.831453 -0.0793778 2504 | -2.13803 0.763767 -0.0160816 2505 | -2.18981 0.741968 0.00976332 2506 | -1.91514 1.2675 -0.0136888 2507 | 1.58 2.75634 -0.260966 2508 | 1.60801 2.73231 -0.263937 2509 | 1.54371 2.77247 -0.258563 2510 | 1.60294 2.77749 -0.312237 2511 | 1.6314 2.75229 -0.303054 2512 | 1.57876 2.78594 -0.314846 2513 | 1.62662 2.79142 -0.331694 2514 | 1.65102 2.76662 -0.326523 2515 | 1.60621 2.7967 -0.342829 2516 | 1.6625 2.79744 -0.352196 2517 | 1.6748 2.78015 -0.341872 2518 | 1.61582 2.70102 -0.275279 2519 | 1.63518 2.72046 -0.310368 2520 | 1.65083 2.73083 -0.333968 2521 | 1.68276 2.73608 -0.34632 2522 | 1.71894 2.74884 -0.354061 2523 | 1.71095 2.78486 -0.350389 2524 | 1.64615 2.80217 -0.359333 2525 | 1.70661 2.80608 -0.36036 2526 | 1.74308 2.75209 -0.353841 2527 | 1.75127 2.78629 -0.350548 2528 | 1.70229 2.8157 -0.375594 2529 | 1.74285 2.80309 -0.36491 2530 | 1.78359 2.75883 -0.345964 2531 | 1.78358 2.78982 -0.346956 2532 | 1.77938 2.80608 -0.357324 2533 | 1.77481 2.81557 -0.376503 2534 | 1.90472 2.81976 -0.339391 2535 | 1.6158 2.66052 -0.275208 2536 | 1.63075 2.68994 -0.329322 2537 | 1.56287 2.65481 -0.29877 2538 | 1.58995 2.67595 -0.349983 2539 | 1.65877 2.71116 -0.340202 2540 | 1.61757 2.6946 -0.377208 2541 | 1.68669 2.71996 -0.347969 2542 | 1.66594 2.7103 -0.372822 2543 | 1.72276 2.72918 -0.360197 2544 | 1.7221 2.72777 -0.388545 2545 | 1.75443 2.73561 -0.384169 2546 | 1.7468 2.73377 -0.363927 2547 | 1.79897 2.74663 -0.380096 2548 | 1.78721 2.74089 -0.360154 2549 | 1.64093 2.7262 -0.411212 2550 | 1.71344 2.73011 -0.412517 2551 | 1.75802 2.74531 -0.407506 2552 | 1.57696 2.71625 -0.390436 2553 | 1.53737 2.70116 -0.358606 2554 | 1.50651 2.66647 -0.292352 2555 | 1.81078 2.75538 -0.391597 2556 | 1.74559 2.76939 -0.417045 2557 | 1.7984 2.7759 -0.405328 2558 | 1.69292 2.76429 -0.42899 2559 | 1.62456 2.75944 -0.419737 2560 | 1.57282 2.74474 -0.391574 2561 | 1.52937 2.72929 -0.355701 2562 | 1.48267 2.69382 -0.281018 2563 | 1.52534 2.7653 -0.352121 2564 | 1.57273 2.77759 -0.396528 2565 | 1.62465 2.7915 -0.416638 2566 | 1.69695 2.79713 -0.434041 2567 | 1.48258 2.73077 -0.285576 2568 | 1.75347 2.7933 -0.426915 2569 | 1.80226 2.8032 -0.410772 2570 | 1.69335 2.81525 -0.411948 2571 | 1.62535 2.8049 -0.386972 2572 | 1.57766 2.79865 -0.362229 2573 | 1.54206 2.78752 -0.330107 2574 | 1.49914 2.76561 -0.27047 2575 | 1.73855 2.81596 -0.379611 2576 | 1.74572 2.81516 -0.41239 2577 | 1.78641 2.81741 -0.396838 2578 | 1.54372 2.77247 0.262801 2579 | 1.58001 2.75634 0.265204 2580 | 1.57877 2.78594 0.319084 2581 | 1.60802 2.73231 0.268175 2582 | 1.60295 2.77749 0.316474 2583 | 1.60622 2.7967 0.347067 2584 | 1.65103 2.76662 0.330761 2585 | 1.63141 2.75229 0.307292 2586 | 1.62663 2.79142 0.335932 2587 | 1.64616 2.80217 0.363571 2588 | 1.67481 2.78015 0.34611 2589 | 1.61583 2.70102 0.279517 2590 | 1.63519 2.72046 0.314605 2591 | 1.65084 2.73083 0.338206 2592 | 1.68277 2.73608 0.350558 2593 | 1.71096 2.78486 0.354627 2594 | 1.66251 2.79744 0.356434 2595 | 1.70662 2.80608 0.364598 2596 | 1.7023 2.8157 0.379832 2597 | 1.71895 2.74884 0.358299 2598 | 1.75128 2.78629 0.354784 2599 | 1.74286 2.80309 0.369146 2600 | 1.73856 2.81596 0.383847 2601 | 1.74309 2.75209 0.358077 2602 | 1.78359 2.78982 0.351192 2603 | 1.77939 2.80608 0.36156 2604 | 1.77482 2.81557 0.380739 2605 | 1.90473 2.81976 0.343627 2606 | 1.7836 2.75883 0.3502 2607 | 1.61581 2.66052 0.279446 2608 | 1.56288 2.65481 0.303008 2609 | 1.63076 2.68994 0.33356 2610 | 1.58996 2.67595 0.354221 2611 | 1.65878 2.71116 0.344439 2612 | 1.61758 2.6946 0.381445 2613 | 1.6867 2.71996 0.352206 2614 | 1.66595 2.7103 0.377059 2615 | 1.72277 2.72918 0.364435 2616 | 1.72211 2.72777 0.392783 2617 | 1.74681 2.73377 0.368163 2618 | 1.75444 2.73561 0.388405 2619 | 1.78722 2.74089 0.36439 2620 | 1.71345 2.73011 0.416754 2621 | 1.75803 2.74531 0.411741 2622 | 1.79898 2.74663 0.384332 2623 | 1.81079 2.75538 0.395833 2624 | 1.57697 2.71625 0.394674 2625 | 1.53738 2.70116 0.362843 2626 | 1.50652 2.66647 0.296589 2627 | 1.79841 2.7759 0.409564 2628 | 1.7456 2.76939 0.421281 2629 | 1.69293 2.76429 0.433228 2630 | 1.62457 2.75944 0.423975 2631 | 1.64094 2.7262 0.41545 2632 | 1.57283 2.74474 0.395811 2633 | 1.52938 2.72929 0.359938 2634 | 1.48268 2.69382 0.285256 2635 | 1.57274 2.77759 0.400766 2636 | 1.52535 2.7653 0.356359 2637 | 1.62466 2.7915 0.420876 2638 | 1.69696 2.79713 0.438279 2639 | 1.48259 2.73077 0.289814 2640 | 1.75348 2.7933 0.43115 2641 | 1.80227 2.8032 0.415008 2642 | 1.62536 2.8049 0.391209 2643 | 1.69336 2.81525 0.416186 2644 | 1.57767 2.79865 0.366467 2645 | 1.54207 2.78752 0.334345 2646 | 1.49915 2.76561 0.274707 2647 | 1.74573 2.81516 0.416626 2648 | 1.78642 2.81741 0.401074 2649 | -0.82271 0.85073 -0.318447 2650 | -0.882391 0.873634 -0.300859 2651 | -0.870983 0.907832 -0.350164 2652 | -0.948345 0.870624 -0.314793 2653 | -0.822035 0.828654 -0.299894 2654 | -0.900099 0.857417 -0.243809 2655 | -0.770218 0.821023 -0.336666 2656 | -0.700019 0.81621 -0.336641 2657 | -0.772546 0.812815 -0.217726 2658 | -0.830459 0.822681 -0.206389 2659 | -0.917013 0.850139 -0.211326 2660 | -0.95773 0.856592 -0.249372 2661 | -0.952895 0.84574 -0.152517 2662 | -0.961795 0.855045 -0.196413 2663 | -0.770403 0.799745 -0.16214 2664 | -0.57262 0.787716 -0.168912 2665 | -0.575502 0.782982 0.00212692 2666 | -0.763124 0.798445 0.00212761 2667 | -0.956958 0.843373 0.00212833 2668 | -1.72559 0.859387 -0.279349 2669 | -1.12737 1.15336 -0.413723 2670 | -0.944242 1.01247 -0.397939 2671 | -0.983818 1.03216 -0.392062 2672 | -0.870027 0.961382 -0.388179 2673 | -1.84737 1.46705 -0.293674 2674 | -1.66782 0.827741 -0.286896 2675 | -0.882389 0.873634 0.305115 2676 | -0.822708 0.85073 0.322703 2677 | -0.948343 0.870624 0.319049 2678 | -0.870981 0.907832 0.35442 2679 | -0.822033 0.828654 0.304149 2680 | -0.770216 0.821023 0.340922 2681 | -0.700017 0.81621 0.340894 2682 | -0.590357 0.81446 0.356182 2683 | -0.641477 0.823748 0.363186 2684 | -0.581099 0.805167 0.250669 2685 | -0.772544 0.812815 0.221982 2686 | -0.900097 0.857417 0.248065 2687 | -0.917011 0.850139 0.215582 2688 | -0.830457 0.822681 0.210645 2689 | -0.957728 0.856592 0.253628 2690 | -0.961793 0.855045 0.200669 2691 | -0.952893 0.84574 0.156773 2692 | -0.770401 0.799745 0.166396 2693 | -0.572618 0.787716 0.173166 2694 | -1.27617 1.10566 -0.42588 2695 | -1.2373 1.11952 -0.424003 2696 | -1.37216 1.01484 -0.424028 2697 | -1.29468 1.0188 -0.419933 2698 | -1.24188 1.02447 -0.412635 2699 | -1.12494 1.04116 -0.401081 2700 | -1.09514 1.03759 -0.393468 2701 | -1.40749 0.918606 -0.388966 2702 | -1.32204 0.923838 -0.385457 2703 | -1.24532 0.914537 -0.363444 2704 | -1.12531 0.953897 -0.370722 2705 | -1.12589 0.919902 -0.340139 2706 | -1.08507 0.979759 -0.381099 2707 | -1.04355 0.982325 -0.367482 2708 | -1.02595 0.91775 -0.32218 2709 | -1.07335 0.922476 -0.345309 2710 | -0.994203 0.872999 -0.265285 2711 | -1.04773 0.900894 -0.264831 2712 | -1.01146 0.874242 -0.219044 2713 | -1.03652 0.85549 -0.155747 2714 | -1.05142 0.848768 0.00212868 2715 | -1.13508 0.830444 0.00212899 2716 | -1.11932 0.82522 -0.1771 2717 | -1.11216 0.868146 -0.265152 2718 | -1.44766 0.845079 -0.315995 2719 | -1.34105 0.830109 -0.289735 2720 | -1.23981 0.83784 -0.287391 2721 | -1.17183 0.796686 -0.174888 2722 | -1.19514 0.79673 -0.213392 2723 | -1.23534 0.804052 -0.242623 2724 | -1.27904 0.780473 -0.219554 2725 | -1.30116 0.777246 -0.194375 2726 | -1.36332 0.777079 -0.205311 2727 | -1.4201 0.768677 -0.215679 2728 | -1.4291 0.784361 -0.249335 2729 | -1.46478 0.795227 -0.266465 2730 | -1.50864 0.790387 -0.259866 2731 | -1.53189 0.78757 -0.249162 2732 | -1.53605 0.774544 -0.222145 2733 | -1.52505 0.769581 -0.195084 2734 | -1.6166 0.818123 0.00213077 2735 | -1.49403 0.763498 -0.176368 2736 | -1.51288 0.786402 0.00213038 2737 | -1.44542 0.761382 -0.188062 2738 | -1.37673 0.77931 0.00212988 2739 | -1.28818 0.764296 -0.157646 2740 | -1.25098 0.772649 -0.133349 2741 | -1.26429 0.792322 0.00212947 2742 | -1.19967 0.777722 -0.14962 2743 | -1.71744 0.850373 -0.188224 2744 | -1.80294 0.898355 -0.191662 2745 | -1.85902 0.949031 -0.177005 2746 | -1.91006 1.01876 -0.164508 2747 | -1.8995 1.01676 -0.248359 2748 | -1.94608 1.10068 -0.145011 2749 | -1.94238 1.09286 -0.220747 2750 | -1.96677 1.18219 -0.139082 2751 | -1.95855 1.17792 -0.202713 2752 | -1.9624 1.28164 -0.143653 2753 | -1.95763 1.27966 -0.194598 2754 | -1.93596 1.44879 -0.147078 2755 | -1.92686 1.45055 -0.185852 2756 | -1.91552 1.57676 -0.149882 2757 | -1.89765 1.57415 -0.190599 2758 | -1.92146 1.5802 0.00213189 2759 | -1.96107 1.28551 0.00213204 2760 | -1.96336 1.19469 0.00213205 2761 | -1.95092 1.09964 0.002132 2762 | -1.89429 1.00082 0.00213179 2763 | -1.84826 0.94449 0.00213162 2764 | -1.78361 0.893854 0.00213138 2765 | -1.71276 0.857518 0.00213112 2766 | -1.63846 0.815328 -0.192959 2767 | -1.94522 1.4462 0.00213198 2768 | -1.89635 1.46327 -0.245092 2769 | -1.9154 1.28058 -0.284144 2770 | -1.90665 1.16911 -0.295517 2771 | -1.88129 1.0828 -0.303033 2772 | -1.85732 1.28521 -0.31884 2773 | -1.82081 1.17603 -0.335622 2774 | -1.19405 0.724697 -0.191343 2775 | -1.21058 0.724728 -0.218651 2776 | -1.23909 0.729921 -0.239378 2777 | -1.27008 0.713201 -0.223019 2778 | -1.28576 0.710913 -0.205166 2779 | -1.27656 0.701727 -0.179118 2780 | -1.25018 0.707651 -0.161887 2781 | -1.21379 0.711248 -0.173428 2782 | -1.44336 0.704835 -0.220272 2783 | -1.44974 0.715956 -0.244138 2784 | -1.47505 0.723661 -0.256287 2785 | -1.50614 0.720227 -0.251605 2786 | -1.52263 0.718231 -0.244018 2787 | -1.52558 0.708996 -0.224856 2788 | -1.51779 0.705474 -0.205667 2789 | -1.49578 0.701163 -0.192391 2790 | -1.46132 0.699659 -0.200687 2791 | -1.25228 0.666687 -0.160406 2792 | -1.21678 0.6702 -0.171665 2793 | -1.27801 0.660912 -0.177214 2794 | -1.28698 0.669869 -0.202622 2795 | -1.27168 0.6721 -0.220039 2796 | -1.24146 0.68841 -0.235997 2797 | -1.21364 0.683345 -0.215777 2798 | -1.19752 0.683314 -0.189139 2799 | -1.46707 0.658893 -0.198254 2800 | -1.44955 0.66394 -0.217359 2801 | -1.50069 0.660357 -0.190165 2802 | -1.52215 0.664566 -0.203111 2803 | -1.52976 0.668 -0.221827 2804 | -1.52688 0.67701 -0.240518 2805 | -1.5108 0.678959 -0.247925 2806 | -1.48046 0.682309 -0.252491 2807 | -1.45578 0.674789 -0.240638 2808 | -1.2448 0.648768 -0.196606 2809 | -1.48927 0.64369 -0.222966 2810 | -1.27616 1.10566 0.43014 2811 | -1.23729 1.11952 0.428261 2812 | -1.37215 1.01484 0.428288 2813 | -1.29467 1.0188 0.424193 2814 | -1.24187 1.02447 0.416892 2815 | -1.09513 1.03759 0.397726 2816 | -1.12493 1.04116 0.405339 2817 | -1.40748 0.918606 0.393226 2818 | -1.32203 0.923838 0.389717 2819 | -1.1253 0.953897 0.37498 2820 | -1.24531 0.914537 0.367702 2821 | -1.08506 0.979759 0.385357 2822 | -1.02594 0.91775 0.326438 2823 | -1.04354 0.982325 0.37174 2824 | -1.07334 0.922476 0.349567 2825 | -1.12588 0.919902 0.344397 2826 | -0.994201 0.872999 0.269542 2827 | -1.04772 0.900894 0.269088 2828 | -1.01145 0.874242 0.223301 2829 | -1.03651 0.85549 0.160005 2830 | -1.11215 0.868146 0.26941 2831 | -1.11931 0.82522 0.181358 2832 | -1.44765 0.845079 0.320254 2833 | -1.34104 0.830109 0.293995 2834 | -1.2398 0.83784 0.291649 2835 | -1.17182 0.796686 0.179145 2836 | -1.23533 0.804052 0.24688 2837 | -1.19513 0.79673 0.21765 2838 | -1.27903 0.780473 0.223814 2839 | -1.30115 0.777246 0.198635 2840 | -1.42909 0.784361 0.253595 2841 | -1.42009 0.768677 0.219939 2842 | -1.36331 0.777079 0.209571 2843 | -1.46477 0.795227 0.270725 2844 | -1.50863 0.790387 0.264126 2845 | -1.53188 0.78757 0.253424 2846 | -1.52504 0.769581 0.199345 2847 | -1.53604 0.774544 0.226407 2848 | -1.63845 0.815328 0.197221 2849 | -1.49402 0.763498 0.180627 2850 | -1.44541 0.761382 0.192322 2851 | -1.28817 0.764296 0.161906 2852 | -1.25097 0.772649 0.137609 2853 | -1.19966 0.777722 0.153878 2854 | -1.80293 0.898355 0.195926 2855 | -1.71743 0.850373 0.192486 2856 | -1.85901 0.949031 0.181269 2857 | -1.91005 1.01876 0.168772 2858 | -1.94607 1.10068 0.149275 2859 | -1.89949 1.01676 0.252623 2860 | -1.96676 1.18219 0.143346 2861 | -1.94237 1.09286 0.22501 2862 | -1.96239 1.28164 0.147917 2863 | -1.95854 1.17792 0.206977 2864 | -1.93595 1.44879 0.151342 2865 | -1.95762 1.27966 0.198861 2866 | -1.91551 1.57676 0.154146 2867 | -1.92685 1.45055 0.190116 2868 | -1.89764 1.57415 0.194863 2869 | -1.89634 1.46327 0.249356 2870 | -1.91539 1.28058 0.288408 2871 | -1.90664 1.16911 0.299781 2872 | -1.88128 1.0828 0.307297 2873 | -1.85731 1.28521 0.323104 2874 | -1.8208 1.17603 0.339886 2875 | -1.21057 0.724728 0.222909 2876 | -1.19404 0.724697 0.195601 2877 | -1.23908 0.729921 0.243636 2878 | -1.27007 0.713201 0.227278 2879 | -1.28575 0.710913 0.209426 2880 | -1.27655 0.701727 0.183378 2881 | -1.25017 0.707651 0.166147 2882 | -1.21378 0.711248 0.177686 2883 | -1.44973 0.715956 0.248398 2884 | -1.44335 0.704835 0.224532 2885 | -1.47504 0.723661 0.260546 2886 | -1.50613 0.720227 0.255865 2887 | -1.52262 0.718231 0.24828 2888 | -1.52557 0.708996 0.229118 2889 | -1.51778 0.705474 0.209928 2890 | -1.49577 0.701163 0.196651 2891 | -1.46131 0.699659 0.204947 2892 | -1.21677 0.6702 0.175923 2893 | -1.25227 0.666687 0.164666 2894 | -1.278 0.660912 0.181474 2895 | -1.28697 0.669869 0.206882 2896 | -1.27167 0.6721 0.224299 2897 | -1.24145 0.68841 0.240255 2898 | -1.21363 0.683345 0.220035 2899 | -1.19751 0.683314 0.193397 2900 | -1.44954 0.66394 0.221618 2901 | -1.46706 0.658893 0.202514 2902 | -1.50068 0.660357 0.194425 2903 | -1.52214 0.664566 0.207372 2904 | -1.52975 0.668 0.226089 2905 | -1.52687 0.67701 0.24478 2906 | -1.51079 0.678959 0.252184 2907 | -1.48045 0.682309 0.256751 2908 | -1.45577 0.674789 0.244898 2909 | -1.24479 0.648768 0.200864 2910 | -1.48926 0.64369 0.227226 2911 | -------------------------------------------------------------------------------- /examples/point_cloud_io.rviz: -------------------------------------------------------------------------------- 1 | Panels: 2 | - Class: rviz/Displays 3 | Help Height: 78 4 | Name: Displays 5 | Property Tree Widget: 6 | Expanded: 7 | - /Global Options1 8 | - /Status1 9 | - /PointCloud21 10 | - /PointCloud21/Status1 11 | - /PointCloud21/Autocompute Value Bounds1 12 | Splitter Ratio: 0.5 13 | Tree Height: 565 14 | - Class: rviz/Selection 15 | Name: Selection 16 | - Class: rviz/Tool Properties 17 | Expanded: 18 | - /2D Pose Estimate1 19 | - /2D Nav Goal1 20 | - /Publish Point1 21 | Name: Tool Properties 22 | Splitter Ratio: 0.588679 23 | - Class: rviz/Views 24 | Expanded: 25 | - /Current View1 26 | Name: Views 27 | Splitter Ratio: 0.5 28 | - Class: rviz/Time 29 | Experimental: false 30 | Name: Time 31 | SyncMode: 0 32 | SyncSource: PointCloud2 33 | Visualization Manager: 34 | Class: "" 35 | Displays: 36 | - Alpha: 1 37 | Autocompute Intensity Bounds: true 38 | Autocompute Value Bounds: 39 | Max Value: 2.30232 40 | Min Value: -2.30147 41 | Value: true 42 | Axis: X 43 | Channel Name: intensity 44 | Class: rviz/PointCloud2 45 | Color: 255; 255; 255 46 | Color Transformer: AxisColor 47 | Decay Time: 0 48 | Enabled: true 49 | Invert Rainbow: false 50 | Max Color: 255; 255; 255 51 | Max Intensity: 4096 52 | Min Color: 0; 0; 0 53 | Min Intensity: 0 54 | Name: PointCloud2 55 | Position Transformer: XYZ 56 | Queue Size: 10 57 | Selectable: true 58 | Size (Pixels): 3 59 | Size (m): 0.01 60 | Style: Points 61 | Topic: /point_cloud 62 | Use Fixed Frame: true 63 | Use rainbow: true 64 | Value: true 65 | Enabled: true 66 | Global Options: 67 | Background Color: 48; 48; 48 68 | Fixed Frame: map 69 | Frame Rate: 30 70 | Name: root 71 | Tools: 72 | - Class: rviz/Interact 73 | Hide Inactive Objects: true 74 | - Class: rviz/MoveCamera 75 | - Class: rviz/Select 76 | - Class: rviz/FocusCamera 77 | - Class: rviz/Measure 78 | - Class: rviz/SetInitialPose 79 | Topic: /initialpose 80 | - Class: rviz/SetGoal 81 | Topic: /move_base_simple/goal 82 | - Class: rviz/PublishPoint 83 | Single click: true 84 | Topic: /clicked_point 85 | Value: true 86 | Views: 87 | Current: 88 | Class: rviz/Orbit 89 | Distance: 9.43795 90 | Enable Stereo Rendering: 91 | Stereo Eye Separation: 0.06 92 | Stereo Focal Distance: 1 93 | Swap Stereo Eyes: false 94 | Value: false 95 | Focal Point: 96 | X: -0.0283656 97 | Y: 1.65889 98 | Z: 0.111699 99 | Name: Current View 100 | Near Clip Distance: 0.01 101 | Pitch: 1.5698 102 | Target Frame: 103 | Value: Orbit (rviz) 104 | Yaw: 4.70358 105 | Saved: ~ 106 | Window Geometry: 107 | Displays: 108 | collapsed: false 109 | Height: 846 110 | Hide Left Dock: false 111 | Hide Right Dock: false 112 | QMainWindow State: 000000ff00000000fd00000004000000000000013c000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000259000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 113 | Selection: 114 | collapsed: false 115 | Time: 116 | collapsed: false 117 | Tool Properties: 118 | collapsed: false 119 | Views: 120 | collapsed: false 121 | Width: 1200 122 | X: 3386 123 | Y: 110 124 | -------------------------------------------------------------------------------- /examples/some_cows.bag: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ANYbotics/point_cloud_io/0bbfa82af45b1ebadccd5deb8c8a79ddf68623e4/examples/some_cows.bag -------------------------------------------------------------------------------- /include/point_cloud_io/Read.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Read.hpp 3 | * 4 | * Created on: Aug 7, 2013 5 | * Author: Péter Fankhauser 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #pragma once 10 | 11 | // ROS 12 | #include 13 | #include 14 | 15 | namespace point_cloud_io { 16 | 17 | class Read { 18 | public: 19 | /*! 20 | * Constructor. 21 | * @param nodeHandle the ROS node handle. 22 | */ 23 | explicit Read(ros::NodeHandle nodeHandle); 24 | 25 | /*! 26 | * Destructor. 27 | */ 28 | virtual ~Read() = default; 29 | 30 | private: 31 | /*! 32 | * Reads and verifies the ROS parameters. 33 | * @return true if successful. 34 | */ 35 | bool readParameters(); 36 | 37 | /*! 38 | * Initializes node. 39 | */ 40 | void initialize(); 41 | 42 | /*! 43 | * Read the point cloud from a .ply or .vtk file. 44 | * @param filePath the path to the .ply or .vtk file. 45 | * @param pointCloudFrameId the id of the frame of the point cloud data. 46 | * @return true if successful. 47 | */ 48 | bool readFile(const std::string& filePath, const std::string& pointCloudFrameId); 49 | 50 | /*! 51 | * Timer callback function. 52 | * @param timerEvent the timer event. 53 | */ 54 | void timerCallback(const ros::TimerEvent& timerEvent); 55 | 56 | /*! 57 | * Publish the point cloud as a PointCloud2. 58 | * @return true if successful. 59 | */ 60 | bool publish(); 61 | 62 | //! ROS node handle. 63 | ros::NodeHandle nodeHandle_; 64 | 65 | //! Point cloud message to publish. 66 | sensor_msgs::PointCloud2::Ptr pointCloudMessage_; 67 | 68 | //! Point cloud publisher. 69 | ros::Publisher pointCloudPublisher_; 70 | 71 | //! Timer for publishing the point cloud. 72 | ros::Timer timer_; 73 | 74 | //! Path to the point cloud file. 75 | std::string filePath_; 76 | 77 | //! Point cloud topic to be published at. 78 | std::string pointCloudTopic_; 79 | 80 | //! Point cloud frame id. 81 | std::string pointCloudFrameId_; 82 | 83 | /*! 84 | * If true, continuous publishing is used. 85 | * If false, point cloud is only published once. 86 | */ 87 | bool isContinuouslyPublishing_ = false; 88 | 89 | //! Duration between publishing steps. 90 | ros::Duration updateDuration_; 91 | }; 92 | 93 | } // namespace point_cloud_io 94 | -------------------------------------------------------------------------------- /include/point_cloud_io/Write.hpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Write.hpp 3 | * 4 | * Created on: Nov 13, 2015 5 | * Author: Remo Diethelm 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #pragma once 10 | 11 | // ROS 12 | #include 13 | #include 14 | 15 | namespace point_cloud_io { 16 | 17 | class Write { 18 | public: 19 | /*! 20 | * Constructor. 21 | * @param nodeHandle the ROS node handle. 22 | */ 23 | explicit Write(ros::NodeHandle nodeHandle); 24 | 25 | /*! 26 | * Destructor. 27 | */ 28 | virtual ~Write() = default; 29 | 30 | private: 31 | /*! 32 | * Reads and verifies the ROS parameters. 33 | * @return true if successful. 34 | */ 35 | bool readParameters(); 36 | 37 | /*! 38 | * Point cloud callback function 39 | * @param cloud point cloud message. 40 | */ 41 | void pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr& cloud); 42 | 43 | //! ROS node handle. 44 | ros::NodeHandle nodeHandle_; 45 | 46 | //! Point cloud subscriber. 47 | ros::Subscriber pointCloudSubscriber_; 48 | 49 | //! Point cloud topic to subscribe to. 50 | std::string pointCloudTopic_; 51 | 52 | //! Path to the point cloud folder. 53 | std::string folderPath_; 54 | 55 | //! Point cloud file prefix. 56 | std::string filePrefix_; 57 | 58 | //! Point cloud file ending. 59 | std::string fileEnding_; 60 | 61 | //! Point cloud counter. 62 | unsigned int counter_ = 0; 63 | 64 | //! Settings for generating file name. 65 | bool addCounterToPath_ = true; 66 | bool addFrameIdToPath_ = false; 67 | bool addStampSecToPath_ = false; 68 | bool addStampNSecToPath_ = false; 69 | }; 70 | 71 | } // namespace point_cloud_io 72 | -------------------------------------------------------------------------------- /launch/example_read.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /launch/example_write.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | point_cloud_io 6 | 0.3.22 7 | Tools to either read and publish or subscribe and write PointCloud2 messages. 8 | 9 | BSD 10 | Peter Fankhauser 11 | Remo Diethelm 12 | Remo Diethelm 13 | Yoshua Nava 14 | 15 | http://github.com/anybotics/point_cloud_io 16 | http://github.com/anybotics/point_cloud_io/issues 17 | 18 | catkin 19 | 20 | 21 | 22 | roscpp 23 | pcl_ros 24 | sensor_msgs 25 | 26 | 27 | gtest 28 | 29 | 30 | -------------------------------------------------------------------------------- /src/Read.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Read.cpp 3 | * 4 | * Created on: Aug 7, 2013 5 | * Author: Péter Fankhauser 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #include "point_cloud_io/Read.hpp" 10 | 11 | #include 12 | 13 | // PCL 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #ifdef HAVE_VTK 20 | #include 21 | #endif 22 | 23 | namespace point_cloud_io { 24 | 25 | Read::Read(ros::NodeHandle nodeHandle) : nodeHandle_(nodeHandle), pointCloudMessage_(new sensor_msgs::PointCloud2()) { 26 | if (!readParameters()) { 27 | ros::requestShutdown(); 28 | } 29 | pointCloudPublisher_ = nodeHandle_.advertise(pointCloudTopic_, 1, true); 30 | initialize(); 31 | } 32 | 33 | bool Read::readParameters() { 34 | bool allParametersRead = true; 35 | allParametersRead = nodeHandle_.getParam("file_path", filePath_) && allParametersRead; 36 | allParametersRead = nodeHandle_.getParam("topic", pointCloudTopic_) && allParametersRead; 37 | allParametersRead = nodeHandle_.getParam("frame", pointCloudFrameId_) && allParametersRead; 38 | 39 | double updateRate; 40 | nodeHandle_.param("rate", updateRate, 0.0); 41 | if (updateRate == 0.0) { 42 | isContinuouslyPublishing_ = false; 43 | } else { 44 | isContinuouslyPublishing_ = true; 45 | updateDuration_.fromSec(1.0 / updateRate); 46 | } 47 | 48 | if (!allParametersRead) { 49 | ROS_WARN( 50 | "Could not read all parameters. Typical command-line usage:\n" 51 | "rosrun point_cloud_io read" 52 | " _file_path:=/home/user/my_point_cloud.ply" 53 | " _topic:=/my_topic" 54 | " _frame:=sensor_frame" 55 | " (optional: _rate:=publishing_rate)"); 56 | return false; 57 | } 58 | 59 | return true; 60 | } 61 | 62 | void Read::initialize() { 63 | if (!readFile(filePath_, pointCloudFrameId_)) { 64 | ros::requestShutdown(); 65 | } 66 | 67 | if (isContinuouslyPublishing_) { 68 | timer_ = nodeHandle_.createTimer(updateDuration_, &Read::timerCallback, this); 69 | } else { 70 | ros::Duration(1.0).sleep(); // Need this to get things ready before publishing. 71 | if (!publish()) { 72 | ROS_ERROR("Something went wrong when trying to read and publish the point cloud file."); 73 | } 74 | ros::requestShutdown(); 75 | } 76 | } 77 | 78 | bool Read::readFile(const std::string& filePath, const std::string& pointCloudFrameId) { 79 | if (std::filesystem::path(filePath).extension() == ".ply") { 80 | // Load .ply file. 81 | pcl::PointCloud pointCloud; 82 | if (pcl::io::loadPLYFile(filePath, pointCloud) != 0) { 83 | return false; 84 | } 85 | 86 | // Define PointCloud2 message. 87 | pcl::toROSMsg(pointCloud, *pointCloudMessage_); 88 | } 89 | #ifdef HAVE_VTK 90 | else if (std::filesystem::path(filePath).extension() == ".vtk") { 91 | // Load .vtk file. 92 | pcl::PolygonMesh polygonMesh; 93 | pcl::io::loadPolygonFileVTK(filePath, polygonMesh); 94 | 95 | // Define PointCloud2 message. 96 | pcl_conversions::moveFromPCL(polygonMesh.cloud, *pointCloudMessage_); 97 | } 98 | #endif 99 | else { 100 | ROS_ERROR_STREAM("Data format not supported."); 101 | return false; 102 | } 103 | 104 | pointCloudMessage_->header.frame_id = pointCloudFrameId; 105 | 106 | ROS_INFO_STREAM("Loaded point cloud with " << pointCloudMessage_->height * pointCloudMessage_->width << " points."); 107 | return true; 108 | } 109 | 110 | void Read::timerCallback(const ros::TimerEvent& /*timerEvent*/) { 111 | if (!publish()) { 112 | ROS_ERROR("Something went wrong when trying to read and publish the point cloud file."); 113 | } 114 | } 115 | 116 | bool Read::publish() { 117 | pointCloudMessage_->header.stamp = ros::Time::now(); 118 | if (pointCloudPublisher_.getNumSubscribers() > 0u) { 119 | pointCloudPublisher_.publish(pointCloudMessage_); 120 | ROS_INFO_STREAM("Point cloud published to topic \"" << pointCloudTopic_ << "\"."); 121 | } 122 | return true; 123 | } 124 | 125 | } // namespace point_cloud_io 126 | -------------------------------------------------------------------------------- /src/Write.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Write.cpp 3 | * 4 | * Created on: Nov 13, 2015 5 | * Author: Remo Diethelm 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #include "point_cloud_io/Write.hpp" 10 | 11 | // PCL 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | namespace point_cloud_io { 19 | 20 | Write::Write(ros::NodeHandle nodeHandle) : nodeHandle_(std::move(nodeHandle)), filePrefix_("point_cloud"), fileEnding_("ply") { 21 | if (!readParameters()) { 22 | ros::requestShutdown(); 23 | } 24 | pointCloudSubscriber_ = nodeHandle_.subscribe(pointCloudTopic_, 1, &Write::pointCloudCallback, this); 25 | ROS_INFO_STREAM("Subscribed to topic \"" << pointCloudTopic_ << "\"."); 26 | } 27 | 28 | bool Write::readParameters() { 29 | bool allParametersRead = true; 30 | allParametersRead = nodeHandle_.getParam("topic", pointCloudTopic_) && allParametersRead; 31 | allParametersRead = nodeHandle_.getParam("folder_path", folderPath_) && allParametersRead; 32 | 33 | nodeHandle_.getParam("file_prefix", filePrefix_); 34 | nodeHandle_.getParam("file_ending", fileEnding_); 35 | nodeHandle_.getParam("add_counter_to_path", addCounterToPath_); 36 | nodeHandle_.getParam("add_frame_id_to_path", addFrameIdToPath_); 37 | nodeHandle_.getParam("add_stamp_sec_to_path", addStampSecToPath_); 38 | nodeHandle_.getParam("add_stamp_nsec_to_path", addStampNSecToPath_); 39 | 40 | if (!allParametersRead) { 41 | ROS_WARN( 42 | "Could not read all parameters. Typical command-line usage:\n" 43 | "rosrun point_cloud_io write" 44 | " _topic:=/my_topic" 45 | " _folder_path:=/home/user/my_point_clouds" 46 | " (optional: _file_prefix:=my_prefix" 47 | " _file_ending:=my_ending" 48 | " _add_counter_to_path:=true/false" 49 | " _add_frame_id_to_path:=true/false" 50 | " _add_stamp_sec_to_path:=true/false" 51 | " _add_stamp_nsec_to_path:=true/false)"); 52 | return false; 53 | } 54 | 55 | return true; 56 | } 57 | 58 | void Write::pointCloudCallback(const sensor_msgs::PointCloud2ConstPtr& cloud) { 59 | ROS_INFO_STREAM("Received point cloud with " << cloud->height * cloud->width << " points."); 60 | std::cout << folderPath_ << std::endl; 61 | std::stringstream filePath; 62 | filePath << folderPath_ << "/"; 63 | if (!filePrefix_.empty()) { 64 | filePath << filePrefix_; 65 | } 66 | if (addCounterToPath_) { 67 | filePath << "_" << counter_; 68 | counter_++; 69 | } 70 | if (addFrameIdToPath_) { 71 | filePath << "_" << cloud->header.frame_id; 72 | } 73 | if (addStampSecToPath_) { 74 | filePath << "_" << cloud->header.stamp.sec; 75 | } 76 | if (addStampNSecToPath_) { 77 | filePath << "_" << cloud->header.stamp.nsec; 78 | } 79 | filePath << "."; 80 | filePath << fileEnding_; 81 | 82 | if (fileEnding_ == "ply") { 83 | // Write .ply file. 84 | pcl::PointCloud pclCloud; 85 | pcl::fromROSMsg(*cloud, pclCloud); 86 | 87 | pcl::PLYWriter writer; 88 | bool binary = false; 89 | bool use_camera = false; 90 | if (writer.write(filePath.str(), pclCloud, binary, use_camera) != 0) { 91 | ROS_ERROR("Something went wrong when trying to write the point cloud file."); 92 | return; 93 | } 94 | } else if (fileEnding_ == "pcd") { 95 | // Write pcd file 96 | pcl::PointCloud pclCloud; 97 | pcl::fromROSMsg(*cloud, pclCloud); 98 | pcl::io::savePCDFile(filePath.str(), pclCloud); 99 | } else { 100 | ROS_ERROR_STREAM("Data format not supported."); 101 | return; 102 | } 103 | 104 | ROS_INFO_STREAM("Saved point cloud to " << filePath.str() << "."); 105 | } 106 | 107 | } // namespace point_cloud_io 108 | -------------------------------------------------------------------------------- /src/read_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * read_node.cpp 3 | * 4 | * Created on: Aug 7, 2014 5 | * Author: Péter Fankhauser 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #include 10 | #include "point_cloud_io/Read.hpp" 11 | 12 | int main(int argc, char** argv) { 13 | ros::init(argc, argv, "read"); 14 | ros::NodeHandle nodeHandle("~"); 15 | 16 | point_cloud_io::Read read(nodeHandle); 17 | 18 | ros::spin(); 19 | return 0; 20 | } 21 | -------------------------------------------------------------------------------- /src/write_node.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * write_node.cpp 3 | * 4 | * Created on: Nov 13, 2015 5 | * Author: Remo Diethelm 6 | * Institute: ETH Zurich, Autonomous Systems Lab 7 | */ 8 | 9 | #include 10 | #include "point_cloud_io/Write.hpp" 11 | 12 | int main(int argc, char** argv) { 13 | ros::init(argc, argv, "write"); 14 | ros::NodeHandle nodeHandle("~"); 15 | 16 | point_cloud_io::Write write(nodeHandle); 17 | 18 | ros::spin(); 19 | return 0; 20 | } 21 | -------------------------------------------------------------------------------- /test/empty_test.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | TEST(Placeholder, emptyTest) { // NOLINT 4 | ASSERT_TRUE(true); 5 | } 6 | --------------------------------------------------------------------------------